Next Article in Journal
Radio Signal Modulation Recognition Method Based on Hybrid Feature and Ensemble Learning: For Radar and Jamming Signals
Previous Article in Journal
Reconstruction of Optical Properties in Turbid Media: Omitting the Need of the Collimated Transmission for an Integrating Sphere Setup
Previous Article in Special Issue
A Fusion Positioning System Based on Camera and LiDAR for Unmanned Rollers in Tunnel Construction
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Review

A Survey of Autonomous Vehicle Behaviors: Trajectory Planning Algorithms, Sensed Collision Risks, and User Expectations

School of Automotive Studies, Tongji University, Shanghai 201804, China
*
Author to whom correspondence should be addressed.
Sensors 2024, 24(15), 4808; https://doi.org/10.3390/s24154808
Submission received: 1 July 2024 / Revised: 19 July 2024 / Accepted: 22 July 2024 / Published: 24 July 2024

Abstract

:
Autonomous vehicles are rapidly advancing and have the potential to revolutionize transportation in the future. This paper primarily focuses on vehicle motion trajectory planning algorithms, examining the methods for estimating collision risks based on sensed environmental information and approaches for achieving user-aligned trajectory planning results. It investigates the different categories of planning algorithms within the scope of local trajectory planning applications for autonomous driving, discussing and differentiating their properties in detail through a review of the recent studies. The risk estimation methods are classified and introduced based on their descriptions of the sensed collision risks in traffic environments and their integration with trajectory planning algorithms. Additionally, various user experience-oriented methods, which utilize human data to enhance the trajectory planning performance and generate human-like trajectories, are explored. The paper provides comparative analyses of these algorithms and methods from different perspectives, revealing the interconnections between these topics. The current challenges and future prospects of the trajectory planning tasks in autonomous vehicles are also discussed.

1. Introduction

Over the past decade, there has been a rapid development of autonomous vehicles (AV), garnering attention from various sectors including academia, industry, and governments. As the autonomous driving systems (ADSs) in these vehicles continue to advance, they hold the potential to revolutionize transportation, yet they are also met with both anticipation and skepticism at the same time.
Autonomous vehicles have demonstrated the capability to avert potential collisions in traffic environments with human errors. They were reported to reduce accidents and enhance road safety in previous investigations [1]. Even with the lane-keeping assistance (LKA) system, a low-level automated driving assistance system (ADAS), which falls short of ADSs, there remains a substantial reduction in the likelihood of potential fatal head-on crashes [2]. Autonomous vehicles are also promising to alleviate traffic congestion and improve transportation efficiency, especially in populated urban areas with dense traffic flows [3,4].
However, despite these advantages, the widespread application of autonomous vehicles still faces significant challenges and issues regarding safety and user experience. On the one hand, the existing surveys indicate that the the current autonomous vehicles continue to be involved in a notable number of traffic safety incidents in the real world [5]. On the other hand, human drivers usually perceive traditional manual driving as safer and more reliable than the currently available autonomous driving experiences [6]. Research has also observed that drivers’ mental cognitive load will increase when traveling by a commercial autonomous vehicle [7]. The development and update of trajectory planning algorithms, which determine the behaviors and motion of autonomous vehicles directly, should take all these issues into account.
At present, there are many studies in the literature that review and analyze various autonomous driving trajectory planning algorithms. These reviews typically focus on the categorization of trajectory planning algorithms, as well as practical research application cases, aiming to differentiate the characteristics among different algorithms.
The classifications employed in these literature reviews typically include the sampling-based algorithms, the optimization-based algorithms, the interpolating curves, or primitives [8,9,10,11,12,13]. The sampling-based algorithms can be further categorized into graph-search-based algorithms and random-sampling algorithms. The optimization-based algorithms are typically categorized into shooting algorithms and collocation algorithms [14]. Parts of the reviews listed out trajectory planning algorithms based on artificial potential fields or virtual force fields, which are usually optimization-based algorithms too [9,10,13]. We discuss these field-based risk estimation methods in a section of this paper separated from the trajectory planning algorithms themselves more systematically. Model predictive control algorithms were also specifically focused on due to their flexibility, which is also present with shooting optimization-based algorithms [9,15,16]. Bio-inspired swarm intelligence algorithms and other types of rule-based algorithms were also introduced [10,12,13]. The algorithms mentioned above convert trajectory planning tasks to mathematical problems with well-defined forms and clear explanatory representations. They are used in combination with other autonomous driving algorithm modules and have clear hierarchical relationships with them, hence also being referred to as pipeline frameworks or modular approaches.
With the evolution of deep learning technology, several review articles have synthesized end-to-end trajectory planning methodologies, such as imitation learning grounded in supervised learning, reinforcement learning leveraging unsupervised learning, and parallel learning integrating confusion learning [17,18]. Other reviews have summarized emerging multimodal large language models for planning [19]. These methodologies form unified machine learning tasks aimed at generating control commands directly from raw input information. While they exhibit significant potential, their black-box nature poses challenges in determining the underlying causes of unexpected behaviors and implementing relevant fixes for commercial deployment, which deserve more systematic research in the future. Therefore, this paper primarily concentrates on local trajectory planning algorithms based on traditional modular approaches.
The autonomous driving system is a complex system, where the selection of planning algorithm types is just one of the influencing factors affecting the final trajectory planning results in complex traffic environments. The algorithm realization details and their relationship with other vehicle modules are equally crucial. Regarding driving safety, there are reviews about the limitations of the current autonomous vehicles and their impacts on transportation accidents and collision risks [5]. Regarding the user acceptance problem, there are reviews about the social interaction behaviors of autonomous vehicles [4] and how to realize personalized automated driving behaviors based on human trajectory data [17,20,21].
However, the aforementioned reviews exhibit several limitations: they often discuss details in different research cases or types of planning algorithms without thoroughly comparing their characteristics; they address the potential risks and issues faced by the current autonomous driving systems without detailing how autonomous driving algorithms specifically mitigate these risks; and they emphasize the user experience and personalized behavior in autonomous driving systems yet provide limited discussion on the relationship between driver behavior and planning algorithms. To address these gaps, this paper re-examines the issues of the collision risk estimations and user expectations of autonomous driving system behavior from the perspective of trajectory planning algorithm design and explores the interconnections between these algorithms and methods.
The contributions are outlined below, as shown in Figure 1:
  • It presents a taxonomy of the trajectory planning algorithms for autonomous vehicles, elucidating the distinctive characteristics of various algorithmic types.
  • It discusses collision risk estimation methods that can parallelly coexist with or are directly integrated into the trajectory planning algorithms across different planning scenarios.
  • It examines diverse approaches to incorporate the data derived from human driver behaviors into the trajectory planning algorithm development process, exploring their implications on user expectations.
In Section 1, we introduce the advantages and challenges associated with autonomous vehicles, along with a concise overview of the literature reviews relevant to trajectory planning. Section 2 delves into various trajectory planning algorithms, offering a comparative analysis. In Section 3, we explore and compare the different risk estimation methods for trajectory planning tasks. Section 4 scrutinizes the methods for utilizing human data in trajectory planning, alongside the discussions of their impact on user expectations. Section 5 discusses the challenges and future perspectives of trajectory planning for autonomous vehicles. In Section 6, the conclusions are provided.

2. Trajectory Planning Algorithms in Autonomous Vehicles

In this section, works of graph-search-based, random-sampling-based, interpolating curves, shooting optimization, collocation optimization, and end-to-end data-driven algorithms for the trajectory planning tasks of autonomous vehicles are reviewed. It is worth noting that the graph-search-based and random-sampling-based algorithms discussed below are also widely applied to global path planning tasks in autonomous driving navigation tasks. However, this article primarily focuses on their applications in collision-free local trajectory planning tasks. These tasks can be accomplished using similar algorithms but with different problem definitions. Additionally, these types of algorithms are also used in the trajectory planning of other controlled objects such as unmanned ground vehicles, unmanned surface vehicles, and unmanned aerial vehicles. Due to space limitations, the properties of these algorithms are analyzed and compared only within the scope of the autonomous vehicle applications in this article. Furthermore, different types of trajectory planning algorithms are often combined in practical applications to address complex driving scenarios.

2.1. Graph-Search-Based Trajectory Planning

Graph search algorithms are based on graph theory, solving trajectory planning problems by searching in graphs. It is necessary to define the method of discretizing the motion state space before graph searches, typically applicable to trajectory planning problems in road traffic environments with relatively regular and deterministic states. This graph can consist of discrete nodes or grids in spatial or temporal dimensions, and edges representing specific executable actions. The core idea is to search for the path with the minimum costs in the graph. These costs are usually the travel distance along the path or trajectory but may also include factors such as smoothness and energy consumption in some studies.
One of the most widely used graph search algorithms is the Dijkstra algorithm [22,23,24], which aims to find the desired path from the starting node to the goal nodes by progressively expanding the edges, maintaining a set of nodes awaiting exploration during searches. At each step, it selects the node with the smallest cost from the starting node for expansion. The primary limitations of this algorithm lie in its inability to handle graphs with edges of negative weights and its tendency to equally explore edges in different directions, often disregarding the relationship between new nodes or edges and the goal nodes. These limitations may lead to computationally intensive problems. However, the algorithm’s flexibility in designing costs allows it to effectively address multi-objective trajectory planning problems without the requirement for the differentiability or continuity of optimization objectives. The uniform-cost search (UCS) algorithm shares nearly identical principles with the Dijkstra algorithm but can provide feasible suboptimal solutions before reaching the final optimal solution [25], making it suitable for planning tasks with limited computational resources. Figure 2 demonstrates the spatio-temporal search graph utilized in [25] for trajectory planning tasks on structured roads. The problems involved in spatio-temporal trajectory planning tasks are further discussed in Section 2.7.
To address the computational efficiency issues of Dijkstra algorithm, popular A* (A-star) algorithms are formed by adding appropriate heuristic terms to the search cost, significantly reducing the number of edge and node accesses during the search process [26,27,28,29]. The added heuristic terms provide estimated cost information between the current search node and the endpoint, thereby accelerating the search process. When the heuristic term consistently represents a lower bound on the actual cost, it ensures the optimality of the search results. However, when the heuristic term may exceed the actual cost, only more greedy suboptimal solutions can be obtained. It is worth noting that, for relatively simple optimization objectives and costs, such as shortest distance, it is convenient to set heuristic terms and utilize A* and its derivative algorithms. However, for graph search planning problems with more complex optimization objectives, designing heuristic terms is often challenging, necessitating the use of exhaustive search algorithms without heuristics and Dijkstra-like algorithm [25,30,31].
There are also several derivative improved versions of the A* algorithm, such as the hybrid A* (HA*) algorithm [32,33], which offers the following enhancements. It adopts a discretization method of planning space using spatial grid points, expands neighbor nodes based on vehicle kinematic constraints, and utilizes a combination of two types of heuristics accordingly, allowing for full consideration of vehicle kinematic constraints and trajectory feasibility. However, a drawback of this algorithm is that it can only yield suboptimal solutions within the feasible discrete space. The more recently proposed traversability hybrid A* (THA*) algorithm further uses estimated traversability to optimize the quality of the planned path and outperformed original hybrid A* algorithm in long distance planning tasks [34].
Adjusting the weights of heuristic terms can also improve the efficiency of A* algorithms. Weighted A* algorithm [35] adjusts the weights of heuristic terms, sacrificing optimality of solutions to enhance search efficiency.
Other A* variants also enhance search efficiency by reusing existing historical search information. The anytime tree-restoring weighted A* (ATRWA*) algorithm [36] reduces search time by reusing search information while sacrificing some optimality. The D* algorithm [37] is capable of planning in partially known and dynamically changing environments, avoiding rebuilding search maps at each adjacent planning step, and instead performs rapid replanning based on existing search results and information about environmental changes. The D* Lite algorithm [38] retains the excellent characteristics of the D* algorithm while having a simpler mathematical implementation. The lifelong planning A* (LPA*) algorithm [39], proposed by the same authors, also possesses similar properties. A new and improved anytime dynamic A* (iADA*) algorithm with path optimization during vehicle movement is claimed to be faster than D* Lite and other similar algorithms [40].
The graph-search-based algorithms discussed and analyzed above are summarized in Table 1.

2.2. Random-Sampling-Based Trajectory Planning

Unlike graph-search-based trajectory planning algorithms, random-sampling-based trajectory planning algorithms do not require predefining the discretization of the planning state space. Instead, they incrementally explore the state space and perform planning tasks by randomly sampling within the state space. Such search algorithms are better equipped to handle irregular geometric properties and partially unknown states in the planning space. They also circumvent the difficulty of setting discrete precision for specific planning tasks encountered by graph-search-based search algorithms.
Random sampling algorithms are still search-based planning algorithms, requiring the construction of a search graph or a search tree during the planning process. Algorithms based on search graphs include the Probabilistic Roadmap (PRM) algorithm [41] and its derivative, the PRM* algorithm [42], searching paths between the starting and end points by the randomly built maps in the state space. The primary challenge faced by PRM algorithms is the complexity of obstacle collision detection and the significant computational time it consumes. In practical applications, a “lazy” approach is often adopted, deferring collision detection steps by first searching for trajectories and then verifying their feasibility [43]. In contrast, Rapid-exploring Random Tree (RRT) algorithms [44], and other search-tree-based random-sampling algorithms derived from them, have gained more widespread application. PRM and RRT algorithms are probabilistically complete. That is, under the condition of a sufficient number of samples, planning problems with feasible solutions can be solved by these algorithms. Commonly used improvement algorithms include the RRT-connect algorithm [45] or Bi-RRT algorithm [46], which simultaneously generate two search trees from the starting and end nodes, as demonstrated in Figure 3, significantly improving the search efficiency.
Some improved versions of RRT algorithms further focus on achieving asymptotic optimality. This means that, with a sufficient number of samples, the obtained feasible solutions can be continuously improved to approach the optimal solution. Compared to the original RRT, the RRT* algorithm [42,47] changes the way newly added nodes search for parent nodes in the search tree and provides rewire steps for existing nodes, ensuring asymptotic optimality. The informed RRT* algorithm [48] accelerates the process of improving the optimal solution by limiting the sampling range of the state space based on the path length information of the current most feasible solution.
The kinodynamic RRT* [49] and kinematic constrained bidirectional RRT* [50] algorithms improve the generation of new nodes by introducing forward-reachable sets or kinematic constraints between nodes, allowing for consideration of the physic constraints of the controlled object during the search process.
However, the vast majority of nodes sampled in RRT and its derivative algorithms, as well as the edges constructed in the search tree, are redundant and do not contribute to the final result, leading to a waste of computational resources. Some random sampling algorithms based on Edge-implicit Random Geometric Graphs (RGG) [51] address this issue. The FMT* algorithm [52] applies the Dijkstra algorithm to RGG, often achieving faster convergence rates than the RRT* algorithm. Combining the heuristic terms from search graphs and the search tree generated by random-sampling give rise to the BIT* [53,54,55] and more sophisticated EIT* [56] algorithms. They simultaneously leverage the advantages of both types of algorithms while ensuring asymptotic optimality of the solution, and are among the most computationally efficient random-sampling-based planning algorithms.
Series of RRT algorithms can be combined with other types of algorithms in autonomous vehicle trajectory planning, like cubic B-spline [57], dynamic window approach [58], and biased sampling distribution generated by neural networks with attention mechanism [59].
While random-sampling-based algorithms possess these advantages, the implementations based on random sampling introduce uncertainty into the final planning results. In trajectory planning tasks such as closed-road scenarios where environmental states are relatively certain and there is a high requirement for the quality of the planned trajectory, deterministic trajectory planning results are typically expected. Therefore, the application of such algorithms is not as widespread as graph-search-based, interpolating curve, and numeric optimization algorithms.
The random-sampling-based algorithms discussed and analyzed above are summarized in Table 2.

2.3. Interpolating Curves and Finite-Sampling-Based Trajectory Planning

Such algorithms generate interpolated trajectories based on control parameters. Reeds–Shepp curves [60] are composed of a series of straight lines and circular arcs, describing forward straight-line, backward straight-line, and constant curvature turning movements of vehicles. Dubins curves [61] are a simplification of Reeds–Shepp curves and can only describe forward and backward straight-line movements. These parameter curves composed of straight lines and circular arcs are suitable for planning the shortest path under constraints such as curvature and start/end position and heading angle, commonly used in low-speed scenarios such as automated parking. Their disadvantage is the inability to guarantee the curvature continuity of the planned result, making them unsuitable for scenarios with higher vehicle speeds. Clothoid curves (or Euler spirals) [62] have a continuous curvature characteristic that linearly changes with the length of the curve. This characteristic is crucial for limiting the lateral acceleration of vehicles and ensuring comfort while traveling along the trajectory, making clothoid curves widely used in various trajectory planning tasks [63,64]. Their disadvantage is the lack of an explicit analytical mathematical expression. Curve construction relies on integral operations and iterative solving, which are relatively time-consuming [65]. Third-order spirals are also a common mathematical form of trajectory planning curves [66], requiring numerical optimization methods to solve unknown parameters. S-curves (Sigmoid) are applied to simple lane-changing trajectory planning tasks in conventional closed-road scenarios [67]. When considering more starting positions and state constraints such as speed and acceleration constraints, polynomial curves [68,69] are more widely used. Polynomial curves have an explicit mathematical form and can ensure the continuity of speed and curvature changes in the planned result.
In addition to the simple interpolating curves mentioned above, spline curves with piece-wise expressions and multiple control points are also commonly used in trajectory planning algorithms. Polynomial spline curves are one of the most common mathematical representations of planned trajectories. Compared to higher-order polynomial curves, they can use fewer parameters to fit longer distance ranges and more complex geometric shapes of vehicle motion trajectories, and are also more calculation-efficient [70,71]. When using fifth- or seventh-order polynomial spline curves, it is possible to minimize trajectory jerk or the third derivative of acceleration (snap) under given control points, which are related to comfort or actuator energy consumption [72,73]. Bézier spline curves, a special form of polynomial spline curves, are also applied in trajectory planning. They provide control points existing in the form of convex hull points to directly and explicitly determine curve parameters, ensuring that the actual curve is enveloped within the convex hull coverage range. This feature allows for the indirect optimization of continuous Bézier spline curves themselves by optimizing the discrete convex hull of Bézier spline curves through optimization [74,75].
Interpolating curves can be combined with other types of trajectory planning algorithms such as graph-search-based collocation numerical optimization algorithms.
These curves can also function independently. Trajectory planning algorithms that generate predetermined numbers of curve samples are referred to as finite-sampling-based trajectory planning algorithms, as illustrated in Figure 4. Typically, they employ either a uniform objective function [76] or the TOPSIS algorithm [77] for sample selection. These finite samplings occur within action spaces or state spaces. For instance, the dynamic window approach samples within the action space defined by velocity, acceleration, and steering angle [78]. Meanwhile, the lattice planner samples within the state space comprising vehicle lateral positions and longitudinal velocities in the Frenét coordinates [79]. While finite-sampling-based algorithms have simple mathematical forms and high computational efficiency, they may struggle to navigate complex dynamic environments and address complex driving goals over extended timeframes.
The algorithms using interpolating curves discussed and analyzed above are summarized in Table 3.

2.4. Shooting Numeric Optimization Trajectory Planning

The shooting methods form optimal control problems (OCPs) for trajectory planning tasks, resulting in sequences of the vehicle’s actions and motion states over time. They typically involve solving an open-loop optimal control problem over a fixed future time interval using discrete time steps, as illustrated in Figure 5. Common types include iterative linear quadratic regulator (iLQR) [80], differential dynamic programming (DDP) [81], and model predictive control (MPC) [15]. These algorithms are not only used for trajectory planning but also for tracking and executing planned results. The OPTPAP algorithm [82] is also a typical algorithm based on OCP formulations.
The MPC algorithms utilizes either nonlinear or linearized vehicle kinematic or dynamic models to predict the vehicle’s state during the planning process, effectively considering complex constraints such as vehicle dynamic constraints. The specific implementation details of MPC algorithms are flexible and diverse. Although the nonlinear MPC (NMPC) algorithm [83], which directly considers nonlinear model constraints, accurately predicts system state changes, it requires significant computational resources. To ensure real-time performance in trajectory planning and tracking tasks, the model needs to be linearized. Specific approaches include the use of linear time-invariant MPC (LTI-MPC) algorithm [84], which directly adopts equivalent linear models based on the flatness properties of vehicle dynamics, linear time-variant MPC (LTV-MPC) algorithm [85], which linearizes the nonlinear model at each control output, and linear parameter-varying MPC (LPV-MPC) algorithm [86], which utilizes linear models in the state space but nonlinear models in the parameter space. Additionally, Hybrid MPC (HMPC) algorithms [87], which switch between different types of models based on rules, and neural network MPC (NNMPC) algorithms [88], which use neural networks as predictive models, also ensure real-time performance. MPC offers flexibility in setting optimization objectives and constraints, with many MPC algorithms incorporating the artificial potential field method discussed in Section 3.4 as part of the risk optimization objective [89,90,91]. Research [92] employs inverse optimal control (IOC) to learn optimal control objectives based on specific task requirements. Planning control algorithms combining MPC with machine learning methods are gaining attention [16].
The iLQR algorithms, compared to the MPC algorithms, usually have more concise mathematical forms. However, their drawback is not explicitly considering complex vehicle dynamics and traffic environment constraints like the MPC algorithms do. Instead, these constraints often need to be added to the optimization objective function through penalty functions [80,93] or augmented Lagrangian methods [94] for iterative solution solving. Additionally, iLQR can only handle linearized state models. On the other hand, iLQR algorithms cannot accelerate the solution process by adopting control time windows inconsistent with the prediction time window as MPC algorithms do. They must solve the entire control sequence within the prediction time window. Despite these limitations, the concise mathematical forms of iLQR algorithms lead to higher computational efficiency [95] and have practical applications in various trajectory planning tasks.
Some newer MPC and iLQR trajectory planning algorithms have taken it a step further by addressing the issue of uncertainty in the behavior of surrounding vehicles. They incorporate the multimodal nature of future trajectories of these vehicles into the optimization process of the algorithms [96,97,98], which provide planning results considering the probability distribution in prediction results. This function also names contingency planning [99]. These algorithms rely on the perception and prediction results of the surrounding vehicles considering uncertainty. Utilizing the multimodal predicted trajectories, these algorithms construct a tree of probable trajectories for the surrounding vehicles, illustrating their behavioral uncertainties. Leveraging the iterative optimization characteristic of MPC and iLQR algorithms, they then determine the optimal action sequence while accounting for these uncertainties.
The shooting numeric optimization planning algorithms discussed and analyzed above are summarized in Table 4.

2.5. Collocation Numeric Optimization Trajectory Planning

Unlike shooting methods, collocation methods often do not directly compute specific sequences of vehicle actions and states. Instead, they directly optimize the parameterized trajectories representing vehicle motion, as illustrated in Figure 6. Throughout the optimization process, constraints are applied to the trajectories to ensure their feasibility. Series of discrete control points determines the shape of trajectories.
Collocation methods often employ trajectory representations such as piece-wise polynomial trajectories or polynomial splines [100]. This is because solutions that adhere to vehicle dynamic constraints in shooting methods can be well-approximated in polynomial form at discrete control points using methods like Hermite–Simpson [14]. Piece-wise clothoid curves connecting control points have also been used in trajectory planning with collocation methods [101].
Collocation methods use sparse and discrete control points instead of the complete control sequence solved in shooting methods, generally formed into nonlinear programming (NLP) problems. Polynomial trajectories in them, having explicit expressions and favorable mathematical properties, allow for direct calculation of gradients of various complex optimization objectives with respect to control point parameters in trajectory planning problems. This allows trajectory planning problems with collocation methods to be solved using general gradient-based nonlinear optimization solvers. Representative examples include the general planning algorithm GCOPTER [102] and the efficient spatio-temporal planning algorithm DFTPAV [103]. The latter achieves more efficient computations compared with many famous shooting optimization planning algorithms while considering complex constraints such as vehicle dynamic constraints, static and dynamic obstacle constraints involving geometric shapes, trajectory high-order continuity, and optimization objectives.
When optimization objectives are expressed in concise quadratic forms based on control point parameters, collocation trajectory planning tasks can be reformulated as quadratic programming (QP) problems. Due to the convexity of these problems, the solutions are guaranteed to be unique. Quadratic programming solvers are not only diverse and mature but also more computationally efficient compared to general nonlinear optimization solvers, making QP methods widely adopted in trajectory planning. Specific applications include smooth multi-objective trajectory tracking [71], highway lane changing [104], and minimum curvature trajectory planning for racing [73]. The DL-IAPS+PJSO algorithm [105] formulates different quadratic programming problems based on the distinct characteristics of lateral planning and longitudinal planning, exhibiting high robustness across various scenarios, including parking situations.
Some collocation-based trajectory planning methods do not rely on smooth continuous polynomial trajectories. The widely used Timed Elastic Band (TEB) algorithm employs line segments and circular arcs to connect discrete control points, solving for the shortest-time trajectory while satisfying constraints such as minimum radius, maximum velocity, maximum angular velocity, and maximum acceleration [106]. Some collocation-based methods directly build optimization objectives based on the relative positions between discrete control points, without concern for specific trajectory forms or adopting piece-wise linear trajectories. They approximate real constraints or optimization objectives related to velocity, acceleration, heading angle, and curvature by these discrete points [107,108].
In addition to conventional nonlinear and quadratic programming algorithms, some intelligent optimization algorithms such as particle swarm optimization have also been applied to trajectory optimization for such problems [109].
The collocation numeric optimization planning algorithms discussed and analyzed above are summarized in Table 5.

2.6. End-to-End Data-Driven Trajectory Planning

With the rapid development of computer hardware performance and the continuous advancement of artificial deep neural network technology, end-to-end trajectory planning methods are gradually demonstrating immense potential. Existing end-to-end trajectory planning algorithms can mainly be categorized into two types: imitation learning (IL) and reinforcement learning (RL) [17].
IL learns the automated driving planning strategy directly from expert demonstration data, without relying on feedback from interaction with the actual environment. Its objective is to make the behavior of the trained model as close as possible to that of the driver data. IL can be further subdivided into three categories: behavior cloning (BC), direct policy learning (DPL), and inverse reinforcement learning (IRL). BC is a passive offline planning strategy learning method that fits driver data to an end-to-end model and then generates behavior that mimics human driving. BC is the most widely used IL method [18,110]. DPL, based on BC, is an iterative online policy learning method. It continuously improves the policy by effectively eliminating past incorrect strategies [111,112]. IRL, on the other hand, processes expert trajectory data to learn the underlying factors from input to output and optimizes actual trajectory planning strategies based on inferred reward functions. IRL is typically implemented using algorithms such as the maximum margin algorithm [113], Bayesian methods [114], and maximum entropy algorithm [115], flexibly approximating driver behavior based on known data.
Unlike IL, RL relies on interaction with the driving environment to obtain reward and penalty feedback data needed for learning and training. The ultimate goal of RL algorithms is to learn a planning strategy to maximize the feedback accumulated over time. Common RL planning algorithms include deep Q-networks (DQN) [116], deep deterministic policy gradient (DDPG) [117], and proximal policy optimization (PPO) [118,119]. Although RL algorithms typically require plenty of training steps and computational resources and have low sampling efficiency and slow convergence, they can learn complex planning strategies and continually adapt to changing environments. RL algorithms that utilize driver operation guidance information [120], as well as algorithms that combine IL with RL [121], can improve the learning efficiency of RL algorithms.

2.7. Spatial and Temporal Spaces, Initial Conditions, and Constraints in Trajectory Planning Algorithms

Different types of trajectory planning algorithms require specific designs of trajectory planning action spaces, state spaces, and constraints, which determine the computational efficiency and quality of trajectory results.
The current hierarchical planning algorithms often project the three-dimensional spatio-temporal trajectory planning problem onto lower-dimensional state spaces in a hierarchical and decoupled manner to reduce computational complexity, solving path planning and speed planning problems sequentially. The decoupled problems not only have smaller state spaces but also have simpler constraint and optimization objective forms, facilitating rapid solutions of complex trajectory planning problems [105,108]. Methods for planning speed curves that avoid obstacles given already planned spatial paths include forward–backward rule-based solvers [31,73] and S–T graph methods [104,108,122].
Meanwhile, some trajectory planning algorithms aim to plan trajectories with paths and speeds simultaneously in a joint time–space domain. This approach, by fully considering the complex interrelationships between vehicle longitudinal and lateral motion characteristics and the detailed patterns of the traffic environment, can yield trajectory planning results that better meet desired objectives. To achieve joint time–space planning in graph-search-based algorithms, appropriate spatio-temporal lattice sampling methods need to be set [25,29,30,123]. Considering that the search process in the spatio-temporal high-dimensional space may result in an exponential increase in the number of samples, some graph-search-based algorithm designs use acceleration interval constraints instead of fixed step-length discrete sampling in the time dimension to effectively avoid the problem of dimension explosion [25,30]. The collocation of numerical optimization algorithms for solving joint time–space problems is reflected in using either the time of discrete control points [106] or the two-dimensional spatial positions at fixed time points [73] as direct optimization objectives, or directly adopting trajectory mathematical forms with time as the independent variable [103].
Apart from QP problems, using shooting or collocation numerical optimization algorithms to solve trajectories may face challenges due to non-convexity and the influence of unexpected local optimal solutions. The most common approach is to integrate numerical optimization methods with other types of trajectory planning algorithms to form hierarchical trajectory planning algorithms, allowing numerical optimization methods to obtain appropriate initial solution conditions. The simplest way is to generate initial solutions based on fixed rules [71,124]. Using graph search methods to generate them is also a common practice. Initial trajectories obtained through graph search can be achieved using Hybrid A* algorithm and its variants in open environments [82,105,125], or by searching for discrete road grid nodes in closed-road scenarios [107,108]. In some algorithm implementations, upper-level graph search trajectory planning algorithms not only provide initial trajectory solutions but also further transform non-convex and redundant obstacle constraints into convex forms suitable for numerical optimization problems based on the initial solution. A common form of constraint transformation is different types of driving corridors [82,107]. Rule-based depth-first search and other methods are also used to generate such corridors [126].
Based on all the discussions in Section 2, the properties of these autonomous vehicle trajectory planning algorithm categories can be concluded and compared briefly in Table 6. The performance of trajectory planning algorithms is closely related to the application scenario, the specific implementation form, and the details of the algorithm. The following conclusions are qualitative analyses and should not be considered definitive.

3. Traffic Environment Collision Risk Estimations for Trajectory Planning Tasks

As autonomous vehicles navigate, they encounter plenty of obstacles within their environment, ranging from various traffic participants and stationary objects to the geometry of the road itself. These obstacles form the navigable areas for autonomous vehicles and pose potential collision risks during transit. Equipped with a diversity of sensors, such as cameras, LiDAR, and millimeter-wave radar, autonomous vehicles can perceive different types of obstacles. Autonomous driving trajectory planning algorithms are imperative to calculate a passable path that circumvents the potential collision hazards based on the current perceptual data. However, raw sensory information often contains redundancies and lacks direct representations of actual potential risk states. Depending on the characteristics of different types of trajectory planning algorithms, it is essential to transform, fuse, and process these raw sensor data into formats directly applicable to trajectory planning tasks. A concrete example is illustrated in Figure 7, where the original multi-view images from cameras have been converted into a mathematical representation of 3D bounding boxes describing the poses and geometries of surrounding obstacles, thereby constraining the state space for the trajectory planning algorithms.
In this section, the methods including surrogate safety measures, parallel safety checkers, bounding boxes, occupancy grids, reachable sets, corridors, and different artificial fields that work parallelly with or are directly integrated into the trajectory planning algorithms of autonomous vehicles are compared and analyzed.

3.1. Surrogate Safety Measures under Specific Conditions

The measures to estimate the potential risks in the driving environment are named traffic conflict-based measures [128] or surrogate safety measures [129] in transportation research. Parts of them are also applied in autonomous driving techniques, especially in advanced driver assistance systems. Measures like time headway (THW) and time-to-collision (TTC) can not only constitute gap and velocity control strategies in adaptive cruise control (ACC) systems [130] but also describe the velocity control behaviors of human drivers and realize personalized strategies in ACC systems [131,132]. Additionally, some studies have found through fixed-base driving simulator experiments and questionnaires that TTC and THW can describe the subjective perception of the risk changes of the lead vehicle in vehicle following scenarios, which formulates some risk prediction models of human drivers [133,134,135,136]. Similar findings based on THW and TTC measures are also extended to other scenarios like lane changes [137]. Different types of time-to-lane-crossing (TLC) metrics are utilized to describe the subjectively perceived risks in curve negotiation scenarios [138,139].
Apart from applications in ADAS, measures like TTC are also utilized in higher-layer decision-making algorithms, which determine the objectives of trajectory planning algorithms. The typical applications are game theoretic decision-making algorithms in lane-changing [140] and intersection [141] scenarios. Considering that the discontinuity of TTC may lead to unrealistic Nash equilibrium in a game, game theoretic algorithms also use acceleration and time measures based on specific assumptions about traffic participants’ behavior to enhance the decision-making performance [142,143].
Despite their ability to describe traffic risk and drivers’ subjective perception in various scenarios, their mathematical forms may lead to undefined or sudden changes in the calculation results under specific conditions. For instance, it was found that the TTC and TLC indicators produced unexpected jumps and could not accurately measure the risks in lane deviation conditions [144]. Moreover, these indicators can only describe specific risk information in complex traffic environments, and they have shortcomings in different performance dimensions [145], thus limiting their application scenarios. Some studies have attempted to use combinations of multiple measures to alleviate these issues and achieve better estimates of traffic risk, whose effectiveness is relatively limited, leaving much room for improvement [128]. Reliable measures are lacking for the lateral traffic risk in scenarios such as lane changes or merges and the general risks in more complex traffic environments [129]. Accordingly, some emerging risk assessment measures based on the above-mentioned simple surrogate safety measures like 2D TTC managed to consider lateral and longitudinal collision risks simultaneously [146,147].

3.2. Safety Checkers Working in Parallel with Trajectory Planning Algorithms

There are comprehensive safety checkers that are applicable to more general and complex driving environments compared with simple surrogate safety measures. At present, they are often used as independent modules to verify the feasibility of planning results.
The Responsibility Sensitive Safety (RSS) model proposed by Mobileye assumes that vehicle drivers need to pay attention to the impact caused by the uncertainty of surrounding traffic participants’ behaviors and uses rule-based mathematical formulas to implement transparent and verifiable real-time traffic risk assessment methods for autonomous driving [148]. These rules describe common-sense behavioral characteristics in human safety driving concepts, essentially considering the thresholds for lateral and longitudinal collision times and safe distances in a comprehensive manner. Specific assumptions such as acceleration thresholds are adopted in the rules, ensuring that the mathematical formulas of these rules correspond closely to the human understanding of common sense [148]. RSS makes autonomous vehicles cautious enough to avoid becoming the cause of traffic accidents as much as possible, and is integrated in Carla 0.9.14 software for autonomous vehicle algorithms simulation [149]. Similarly, Nvidia proposes the Safety Force Field (SFF) model as another set of risk assessment methods for planning control behaviors [150]. Unlike RSS, SFF judges risks based on the intersection of the trajectories of different traffic participants and no longer aims to increase the size of potential risks as the ultimate goal. Although there are specific mathematical differences between RSS and SFF, they have high conceptual similarity and can be used interchangeably, showing similar performance in the Carla simulation environment [151].
However, studies such as [152] argue that the approach of assuming that all traffic participants always follow the same common-sense rules and defining the reasonable behavior of autonomous vehicles based on safe distances, as adopted by RSS and similar methods, is unreasonable. Because even if the behavior of autonomous vehicles themselves is reasonable, other traffic participants may still exhibit behavior inconsistent with the expectations [152]. Therefore, this study proposes to address this issue by considering all the legal behaviors of other traffic participants.
Apart from the rule-based parallel safety checkers discussed above, there are other safety checkers based on the maneuver-oriented motion prediction of other traffic participants. Most of these are data-driven approaches utilizing machine-learning algorithms. For example, structured Bayesian networks trained on datasets can infer collision probabilities based on the predicted future states of the traffic participants, with these predicted future states obtained from Kalman filter models [153]. Future collision probabilities can also be quantified by heuristic Monte Carlo sampling, with the future states estimated from extended Kalman filtering models [154]. Furthermore, the emerging diverse data-driven end-to-end traffic motion prediction approaches provide more reliable future state predictions over longer time ranges compared to the traditional Kalman filter models [155]. The prediction results for the concerned traffic participants in these approaches are in the form of behavioral intention classifications, unimodal trajectories, or multimodal trajectories [155]. Specifically, the safety checkers based on long-short-term memory networks [156] and graph neural networks [157] provide promising risk estimation results based on the predicted trajectories.

3.3. Bounding Boxes, Occupancy Grids, Reachable Sets, and Driving Corridors

The most common method of integrating traffic risk modeling into autonomous driving trajectory planning algorithms is the description of whether vehicles can pass through a specific area or avoid collisions, including bounding boxes, reachable sets, and driving corridors. These methods are only used to delineate the boundaries of the passable area for vehicles themselves, without considering the different levels of potential risk at different positions within the passable area based on the motion state of the vehicles.
The trajectory planning methods in structured roads typically employ passive reactive collision check methods, which do not explicitly describe passable areas but instead perform collision checks during the trajectory planning process to determine if the planned trajectory is feasible [76,79,158]. Collision checks are usually based on the geometric bounding boxes of the vehicle and other traffic participants [74,77,108], as illustrated in Figure 8. In specific scenarios such as lane changing, collision detection can be further simplified to one-dimensional distance constraints [159].
With the development of advanced end-to-end autonomous vehicle perception and prediction algorithms, three-dimensional occupancy grids become promising substitutes for the traditional bounding boxes. They provide detailed spatial occupancy information of the obstacles in the environment beyond simple bounding size and position information, providing finer geometry details and possessing privileges in describing out-of-vocabulary objects [160]. Currently, the most popular and efficient realizations are based on emerging Transformer networks [161].
Reachable sets encompass the collection of states that autonomous driving vehicles can reach over time starting from a series of initial states without collisions, and they have been widely applied in planning algorithms [162,163]. Tools like SPOT have been developed for generating reachable sets [164]. Improved reachable sets can handle environments of arbitrary complexity [163]. Apart from the motion dynamics of transportation participants, some reachable set designs also consider the visibility of the areas around the driver’s field of vision [165,166]. The reachable set considering the above-mentioned two types of environment information is illustrated in Figure 9. The reachable sets mentioned above are suitable for conducting reachability analysis in complex traffic environments, generating passable areas for autonomous vehicles, effectively exploring the available state spaces and the topological structure for driving tasks, even detecting narrow passages.
Similar to the concept of reachable sets are driving corridors. Driving corridors are typically generated based on the initial reference trajectory and environmental obstacle constraints. Some examples of convex driving corridors and their relationships with planning algorithms are provided in Section 2.7. Driving corridors transform the original complex and multi-source constraint information into convex constraints for numeric optimizations [103,126], as illustrated in Figure 10. They can be considered as the collection of feasible motion states provided by the high-level decision module or based on reachable sets, simplifying the trajectory planning problem. If no feasible driving corridor exists in a certain area, all the planning results in that area are considered unreasonable [167].
Bounding boxes, reachable sets, and driving corridors provide similar information about passable areas. Therefore, some new planning algorithms propose to uniformly handle three different types of risk constraints in optimization objectives, ensuring the compatibility of planning algorithms with different types of upstream perception and prediction information [98]. Although the traffic risk considerations applied to trajectory planning algorithms effectively describe information about passable areas in the environment to avoid collisions, they typically assume that the predicted trajectories are stably executed and cannot describe the potential risk levels caused by changes in the relative position and relative velocity. Although some planning algorithms introduce the Euclidean distance between the vehicle and the boundaries modeled by the three methods into the optimization objectives [98,168], which can introduce the modeling of potential risk levels to some extent, they still overlook the nonholonomic dynamic properties of vehicles and ignore the differences in the potential risk characteristics in the lateral and longitudinal directions of vehicles.

3.4. Potential Fields, Virtual Force Fields, and Composite Risk Fields

Various virtual field methods have been widely used not only to achieve obstacle avoidance but also to measure the potential risks in the driving environment. These fields can be based on the concrete artificial potential fields representing different traffic participants and relative movements between roads in the tangible traffic environment [169], or they can be abstract virtual force fields based on temporal distances beyond traditional spatial distances in the state space during trajectory planning [35].
The traditional artificial potential field methods establish a single potential field in the traffic environment, as illustrated in Figure 11. The typical designs often include a virtual repulsive force that decays with the Euclidean distance to obstacles, penalizing close relative positional relationships during trajectory planning [89,170]. To further consider the risk impact caused by relative motion, some improved artificial potential field methods have potential function distributions that change with the relative velocity between the ego vehicle and obstacles [91,171,172]. This design is similar to considering the minimum safe distance with respect to the relative velocity but extends it to two-dimensional space rather than being limited to one-dimensional longitudinal risk considerations in specific scenarios. Some artificial potential field designs further consider the impact of relative acceleration [169]. Although these artificial potential field designs can achieve safety goals such as minimum safe distance, they often do not represent the characteristics of real traffic collision risks and do not provide clear physical interpretations of potential collision risks like safety surrogate metrics such as time headway (THW), time to collision (TTC), and post-encroachment time (PET) [129]. On the other hand, the existing artificial potential field methods provide almost no quantitative parameter calibration methods to accurately measure the traffic risk conditions. Only a small amount of literature provides qualitative analyses of parameter calibration methods [171]. Despite the shortcomings of the existing artificial potential field methods, they provide a unified approach for modeling different sources of risks in complex traffic environments and can consider the potential risks brought by relative positions and relative velocities before real collisions happen. The relationship between artificial potential field designs and the desired risk goals in trajectory planning algorithms requires further exploration.
In recent years, the introduction of composite risk field methods has made it possible to address the issues with single artificial potential fields, achieving more precise and detailed modeling of traffic risks. The critical idea is to first model the influences or risk consequences of obstacles in the traffic environment using one artificial field, and then model the probability of future events in the traffic environment using another artificial field. The final risk estimation result therefore comes from the interactions between these two fields, as illustrated in Figure 12. Probabilistic Driving Risk Field (PDRF) assumed the probability distribution of the lateral and longitudinal acceleration magnitude of the ego vehicle over a fixed future time period and modeled the composite risks using the method of the overlap area of the vehicle geometric bounding boxes considering future motion and the probability distributions of the accelerations in this area [144]. Driver’s Risk Field (DRF) is proposed to represent the subjective judgment of the driver on the possible future positions of the ego vehicle within a look-ahead time range interval [173]. The DRF extends along the predicted trajectory of the vehicle and changes its geometric shape based on the ego vehicle’s state, such as velocity and steering wheel angle. The dual integration result of the DRF multiplied by the field representing the influence of obstacles provides the final estimate of the traffic environment risk [173,174]. In addition, related studies have proposed specific procedures and methods for calibrating DRF parameters using driving simulator experimental data [173] or real vehicle experimental data [174]. Both PDRF and DRF rely on two-dimensional integration operations, requiring a considerable amount of computational resources [144,173]. This disadvantage is particularly evident for DRF, which needs to perform two-dimensional integration over large spatial areas in the traffic environment. The two-dimensional integration operations also make it difficult for PDRF and DRF to provide the gradient information of estimated risk magnitude with respect to vehicle states. In contrast, the traditional single artificial potential field methods can obtain this gradient information at a low cost [91], speeding up the convergence of numerical optimization trajectory planning algorithms. The Geometric Driver Risk Field (GDRF) algorithm is based on more efficient geometric intersection calculations rather than two-dimensional integrations, retaining the benefits of the comprehensive risk modeling details inherent in composite risk field methods while significantly enhancing the computational efficiency for real-time trajectory planning tasks. GDRF can also be integrated with gradient-based collocation numeric optimization planning algorithms [175].
The risk estimation methods in trajectory planning discussed and analyzed above are summarized in Table 7.

4. Human Driver Behaviors and Expected Autonomous Vehicle Trajectory Planning Behaviors

Various survey-based theoretical models, including the Technology Acceptance Model (TAM), Unified Theory of Acceptance and Use of Technology (UTAUT), Theory of Planned Behavior (TPB), and Innovation Diffusion Theory (IDT), have been employed in previous studies to identify the factors influencing users’ expectations of autonomous vehicles [176]. For instance, studies utilizing TAM have shown that a driver’s trust is crucial in shaping their perception of risks, usefulness, and intention to adopt autonomous vehicles [177]. To enhance driver trust, TAM highlights several key aspects: system transparency requires vehicles to demonstrate consistent and predictable behaviors; technical competence demands high performance with minimal errors across various scenarios; and situation management expects the provision of adequate and responsive alternative solutions under the driver’s control [177]. Achieving these aspects necessitates appropriate actions that align with the driver expectations, which in turn require a thorough understanding of the complex interactions between the traffic participants and the environment. Accordingly, other studies have stated that personalized or human-like driving behaviors in autonomous vehicles have the potential to enhance road safety, transportation efficiency, and human-centric mobility [21].
Companies like Bosch have already introduced commercial solutions for personalized autonomous driving behaviors, such as Dynamic Distance Assist (DDA) [178]. However, the existing solutions can only achieve personalized driving behaviors on relatively basic and well-defined dimensions, such as following distance. The realization of more complex and human-like personalized autonomous driving behaviors remains to be further explored. This requires an in-depth discussion on the utilization of driver behavior data.
In this section, methods including imitation learning, preference learning, and driver behavior modeling that can incorporate the data of human driver behaviors into trajectory planning algorithms are investigated. The critical ideas of the three methods are illustrated in Figure 13. The influences of these methods on users’ subjective expectations are also discussed.

4.1. Mimicking Human Trajectories Directly: Imitation Learning and Data-Driven Model Fitting

Section 2.6 has introduced the imitation learning end-to-end trajectory planning algorithms. These end-to-end data-driven methods fully utilize the flexibility and generalization capabilities of advanced deep learning techniques to directly imitate the manual driving trajectory data collected from human drivers.
In addition, some methods adopt model-based data-driven driver trajectory imitation learning approaches. These methods do not directly learn driver trajectory data themselves but instead establish parameterized models combined with other trajectory planning algorithms representing different dimensions of driver behavior properties [20], naming implicit personalization models. The most common models include Hidden Markov Models (HMM) and Gaussian Mixture Models (GMM), either individually or in combination, which have been found through real vehicle validation to fit real longitudinal and lateral driving behavior data [179,180]. Maximum Likelihood Estimation (MLE) [181], Recursive Least-Squares (RLS) [182], and logistic regression models [183] have also been applied to personalized model establishment. The study in [184] not only employs the Nelder–Mead simplex optimization method for the offline identification of driver steering model parameters but also utilizes the unscented Kalman filter (UKF) for online real-time parameter learning. Unlike imitation learning methods, parameterized models are typically limited to more specific driving tasks rather than general autonomous driving planning tasks. However, these models’ methods offer better interpretability, directly representing the characteristics of different driver behaviors clearly. These model-based methods are reported to not only improve the driver acceptance of the system under specific conditions but also reduce the false alarm rates of ADAS systems [180].
Other popular methods include the identification and classification of the driving styles of human drivers [185,186] and designing distinguished trajectory planning strategies for different styles accordingly [90].
Although the methods mentioned above, which directly mimic human driver trajectories or driving styles, show promising results, there is still controversy surrounding their effectiveness. Some studies have indicated that drivers’ preferences and expectations of autonomous vehicle behaviors differ from their own driving behaviors observed in the collected manual driving trajectory data across diverse driving scenarios [187,188,189], presenting a challenge to these mimicking methods. These differences have been found to be associated with specific driving scenarios [188]. For instance, the relationship between personalized speed control and subjectively perceived safety is moderated by trust in autonomous vehicles. Personalized speed control behavior only positively influences drivers’ subjectively perceived safety when they lack trust in the autonomous driving system [190]. Therefore, it is imperative for future research to further explore and determine the specific autonomous driving scenarios and the specific user groups for which these mimicking methods are suitable.
Figure 13. The illustrations of methods incorporating data of human driver behaviors into trajectory planning algorithms, including imitation learning, preference learning, and driver behavior modeling.
Figure 13. The illustrations of methods incorporating data of human driver behaviors into trajectory planning algorithms, including imitation learning, preference learning, and driver behavior modeling.
Sensors 24 04808 g013

4.2. Learning from Human Feedback: Preference Learning

Different from those methods discussed in Section 4.1, some studies aim to learn drivers’ experience and preference knowledge through direct feedback information from drivers rather than indirectly collected manual driving data.
Preference-based learning methods have been widely used in the field of robotics to help complete complex operational tasks without explicitly determining the reward functions and their parameters. These methods utilize the preference information from human users about specific trajectories to assist in task completion. Similar to imitation learning, preference-based learning can either directly learn the optimal strategy itself [191] or learn a lower-dimensional and more interpretable reward function [192]. Such methods have also been applied to learning the driver behavior preferences in automated driving vehicles [193,194]. The reward function is typically a linear combination of the parameter set [195]. Research has also used neural networks to learn the nonlinear relationship between the size of the reward function and the parameters of the reward function [194]. Another study further combined preference-based learning with imitation learning of user-demonstrated trajectories to achieve a hybrid strategy learning method [196].
Preference-based learning demonstrates the potential to learn complex preference behaviors using minimal data. However, in practical applications, it typically requires dozens or even hundreds of inquiries for drivers to repeatedly experience similar driving scenarios to learn the final goal [197]. Some research has further incorporated the subjective feedback acquisition of preference features based on preference inquiries, which improves the convergence speed of the learning process compared to basic preference-based learning methods [198]. In specific tasks like the preference learning of lane centering control (LCC) behaviors [199], the feedback query method and the reward function parameter update policies can be designed in detail to learn personalized preferences within only a dozen inquiries. Therefore, such methods need to be further explored in combination with specific practical application scenarios to explore further application possibilities.
The efficiency issue limits the application of preference learning to autonomous driving tasks. In addition, recent research has also focused on large language models based on Transformer architecture for human preference learning to understand driver feedback information and adjust the behavior of automated driving vehicles accordingly, showing potential applications [200,201].

4.3. Utilizing Human Behavior Mechanism: Driver Modeling

Apart from utilizing human trajectory data and human feedback, some research aims to achieve driving behaviors that align with drivers’ expectations through modeling the mechanism behind drivers’ behavior.
Traditional model predictive control (MPC) algorithms, besides optimizing the objectives related to obstacle avoidance, driving efficiency, and smoothness, typically include an optimization objective related to the deviation distance from the lane centerline to steer the trajectory as close to the lane centerline as possible [90,91]. However, the assumption of driving along the lane centerline does not align with real drivers’ driving habits. Studies have found that human drivers typically adjust the vehicle’s lateral position with specific patterns during the different phases of cornering, with trajectories closer to the lane centerline being relatively less common [202,203]. To address this issue, studies from different institutes collected extensive data on the lane-keeping processes from drivers and analyzed the lateral offset patterns in these data. Based on these preference patterns, they dynamically generated driving corridor regions and set lateral position constraints for MPC algorithms, achieving human-like driving trajectories by minimizing the steering wheel manipulation rather than following the lane centerline [204,205]. The dynamically generated driving corridors based on lateral offset patterns can be viewed as a concise and practical method for modeling driver behavior mechanisms. When it comes to the velocity control of vehicles, the intelligent driver model (IDM) and its variants are widely adopted for the longitudinal motion planning of autonomous vehicles [206].
The in-depth research on driver perception and behavior also poses new challenges to the other common assumptions or optimization objectives used in the existing automated driving planning and control algorithms. As early as 1970, researchers found that drivers are not sensitive to the relative distance deviation between two points in their forward view [207,208], challenging the modeling of driver behavior based on the deviation distances of preview points. Studies in psychology have found that drivers cannot accurately estimate the curvature of the road ahead [209]. Research in traffic engineering has found that one of the main reasons for accidents on curved roads is drivers’ incorrect estimation of the curvature of sharp curves, providing evidence for this [210]. Therefore, planning algorithms that assume drivers can estimate the curvature of upcoming curves to adjust their steering behavior may not consider this perceptual regularity of drivers [211]. The parts of planning algorithms with trajectory curvature as the sole optimization objective [158,212] may overlook drivers’ deep-seated psychological expectations and behavior mechanisms.
Furthermore, the research on driver perception and behavior can provide new insights for the algorithm design in automated driving systems. Researchers have found that drivers’ gaze behavior during cornering is directly related to their steering control behavior and the desired driving trajectory [213,214]. Moreover, more research indicates that drivers’ steering control processes mainly rely on visual information [215].
The research on which key features of visual information drivers use to produce corresponding driving behaviors has a history of more than forty years. Due to the relative motion in the environment and the visual persistence effect of drivers, all the visible surrounding objects will leave plenty of radial line-shaped images in the human field of view, known as optic flow. Studies have shown that drivers can use optic flow information to estimate the vehicle speed [216], heading angle [217], and future vehicle motion trajectories [218,219]. Adding optic flow information to flickering visual images can significantly improve drivers’ steering performance, with more pronounced effects than increasing frame rates [215]. This confirms the mechanism of drivers’ predictions of vehicle motion based on optic flow. Experiments have also shown that, during cornering, drivers’ preview gaze positions alternate between closer and farther positions along the road at regular intervals. Drivers’ preview gaze behavior at closer road positions, called guiding fixation (GF), is directly related to drivers’ current steering control objectives [220]. Drivers’ preview gaze behavior at farther road positions, known as look-ahead fixation (LAF), involves drivers planning the future driving trajectories and assessing the future risks [221]. Research found that changes in the angular projection of the front vehicle in the field of view are directly related to drivers’ subjective perceptions of safety margins and collision risks [134].
Applying the findings of the above studies to autonomous vehicle algorithms has been explored preliminarily. The challenge lies in how to transform the diverse perception and behavior patterns discovered into models that can be integrated and applied to trajectory planning algorithms. The typical models that interconnect drivers’ visual gazing behaviors and curve negotiation behaviors include the tangent point models [213,222] and waypoint models [219,221]. However, these models are usually closed-loop reactive control models based on simple state parameters and can only describe the driving behaviors in specific scenarios without fully considering the complex prediction, decision-making, and planning behaviors of real drivers in actual driving tasks. A comprehensive and systematic review [223] suggests that a unified and universally applicable driver behavior model based on control theory, perceptual psychology, and neuroscience is likely to become possible in the near future. The composite risk fields introduced in Section 3.4 try to establish subjective risk models based on drivers’ subjective attentions considering the steering behaviors and preview behaviors in complex environments applicable for more complex planning tasks.
Ongoing studies are trying to mitigate the gap between complex driver behavior modeling and trajectory planning algorithm development. For example, the AV-IDM model is proposed to enhance the traditional longitudinal intelligent driver model for lateral and longitudinal motion planning simultaneously and human-like reactive trajectory generations, with the parameters calibrated with the fractional factorial design approach [224]. The GDRF model is integrated with hierarchical trajectory planning algorithms to realize human-like multi-objective trajectory planning in various driving scenarios [175]. An end-to-end framework PHTPM that mimics the drivers’ preview behaviors around the tangent point and the preview point is proposed for trajectory planning tasks [225]. A linear driver model is also proposed to generate the waypoints ahead, reflecting the human driver preferences for trajectory planning [226].
The methods utilizing human data in trajectory planning discussed and analyzed above are summarized in Table 8.

5. Challenges and Future Perspectives

Based on the discussions in the previous sections, the challenges faced by the industry and autonomous vehicles considering trajectory planning tasks can be summarized as follows:
  • Technique Requirements: The continuously evolving market for autonomous passenger vehicles and robotaxis is placing increasingly higher demands on the performance of autonomous driving techniques. Each type of trajectory planning algorithm has its limitations. Even relatively general trajectory planning algorithms may encounter specific issues in certain driving conditions. Ensuring the robustness and high performance of planning algorithms in complex scenarios with uncertainties from various sources poses a significant challenge. However, these efforts are essential for transportation safety and the widespread adoption of autonomous technology.
  • Safety and Regulations: The ongoing popularization of autonomous driving technology faces various legal and regulatory restrictions and encounters complex traffic scenarios where autonomous vehicles, traditional manually driven vehicles, pedestrians, and non-motorized vehicles coexist. Autonomous vehicles need to handle complex safety objectives in real time. The current trajectory planning algorithms primarily utilize fast and direct methods such as bounding boxes, reachable sets, and corridors. Additionally, incorporating considerations for the potential risks arising from environmental uncertainties, driver behaviors, and vehicle dynamics into the algorithms is crucial for ensuring road safety.
  • User Experience and Market Expectations: The user experience of autonomous driving systems is becoming a key factor influencing their market competitiveness and adoption levels. The current manually set objectives and parameters in trajectory planning algorithms may not align with diverse users’ subjective expectations. Methods such as imitation learning, preference learning, and driver behavior modeling have different limitations in addressing this issue. More systematic investigations are needed to develop approaches for designing trajectory planning algorithms oriented towards user experience.
Accordingly, considering the challenges mentioned above, potential future perspectives could be outlined below:
  • Enhanced Objective Integration: Faced with the requirements from planning task constraints and user demands, it is essential to incorporate more comprehensive and detailed objectives concerning various real-world driving tasks into the designs of trajectory planning algorithms. Precisely quantifying these needs through objective metrics and high-quality datasets will make significant differences.
  • Advanced Trajectory Planning: As the application scenarios of autonomous driving systems continue to expand and the requirements for the takeover rates increase, more advanced trajectory planning algorithms capable of handling complex tasks will emerge. For example, adopting spatio-temporal trajectory planning instead of separate path and velocity planning can yield more optimal results in complex scenarios. Additionally, enhancing the consideration of the behavioral uncertainty among the traffic participants based on the available perception and prediction information is a promising development direction.
  • Safety and Risk Estimation: Safety and regulatory concerns call for integrating more advanced, realistic, yet efficient methods for estimating the potential collision risks into planning algorithms to promote safer driving behaviors. For instance, advanced occupancy prediction technologies that provide comprehensive information about the geometries, motions, statuses, and behavioral intentions of traffic participants or other obstacles deserve further investigation. These technologies can be integrated with both end-to-end planning algorithms and traditional modular approaches.
  • Human-like and Interpretable Planning: Techniques that generate more consistent, interpretable, and human-like trajectory planning results will attract more attention. It is critical to cultivate human-like driving behaviors that meet users’ expectations through the systematic development of trajectory planning algorithms and diverse parameter tuning methods. Simultaneously, developing more reliable end-to-end trajectory planning methods based on data-driven approaches, while providing more interactions and feedback information, may alleviate users’ concerns.

6. Conclusions

This review paper encompasses numerous studies concerning the behaviors of autonomous vehicles and the realization of trajectory planning tasks, covering three main topics: trajectory planning algorithms, the collision risk estimation methods involved in these algorithms, and approaches for achieving trajectory planning results that align with the user expectations.
In summary, the discussed planning algorithms are categorized into various types, including graph-search-based, random-sampling-based, interpolating curves, shooting optimization, collocation optimization, and end-to-end algorithms. The risk estimation methods encompass surrogate safety measures, parallel safety checkers, bounding boxes, occupancy grids, reachable sets, corridors, and various artificial fields. Additionally, user experience-oriented approaches utilizing human data such as imitation learning, preference learning, and driver behavior modeling are explored.
This paper provides a comprehensive comparative analysis of the algorithms and techniques, uncovering their interconnections between the three topics.

Author Contributions

Conceptualization, T.X. and H.C.; methodology, T.X. and H.C.; formal analysis, T.X. and H.C.; investigation, T.X.; resources, H.C.; writing—original draft preparation, T.X.; writing—review and editing, H.C.; visualization, T.X.; supervision, H.C. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

No new data were created or analyzed in this study.

Acknowledgments

We acknowledge the support from all the members in chassis electronic control system laboratory, School of Automotive Studies, Tongji University.

Conflicts of Interest

The authors declare no potential conflicts of interest with respect to the research, authorship, and publication of this article.

References

  1. Bohm, F.; Häger, K. Introduction of Autonomous Vehicles in the Swedish Traffic System: Effects and Changes Due to the New Self-Driving Car Technology; Uppsala University: Uppsala, Sweden, 2015. [Google Scholar]
  2. Utriainen, R.; Pöllänen, M.; Liimatainen, H. The Safety Potential of Lane Keeping Assistance and Possible Actions to Improve the Potential. IEEE Trans. Intell. Veh. 2020, 5, 556–564. [Google Scholar] [CrossRef]
  3. Zhao, J.; Zhao, W.; Deng, B.; Wang, Z.; Zhang, F.; Zheng, W.; Cao, W.; Nan, J.; Lian, Y.; Burke, A.F. Autonomous driving system: A comprehensive survey. Expert Syst. Appl. 2024, 242, 122836. [Google Scholar] [CrossRef]
  4. Wang, W.; Wang, L.; Zhang, C.; Liu, C.; Sun, L. Social Interactions for Autonomous Driving: A Review and Perspectives. Found. Trends® Robot. 2022, 10, 198–376. [Google Scholar] [CrossRef]
  5. Chougule, A.; Chamola, V.; Sam, A.; Yu, F.R.; Sikdar, B. A Comprehensive Review on Limitations of Autonomous Driving and Its Impact on Accidents and Collisions. IEEE Open J. Veh. Technol. 2024, 5, 142–161. [Google Scholar] [CrossRef]
  6. Brell, T.; Philipsen, R.; Ziefle, M. sCARy! Risk Perceptions in Autonomous Driving: The Influence of Experience on Perceived Benefits and Barriers. Risk Anal. 2019, 39, 342–357. [Google Scholar] [CrossRef]
  7. Stapel, J.; Mullakkal-Babu, F.A.; Happee, R. Automated driving reduces perceived workload, but monitoring causes higher cognitive load than manual driving. Transp. Res. Part F Traffic Psychol. Behav. 2019, 60, 590–605. [Google Scholar] [CrossRef]
  8. Gonzalez, D.; Perez, J.; Milanes, V.; Nashashibi, F. A Review of Motion Planning Techniques for Automated Vehicles. IEEE Trans. Intell. Transp. Syst. 2016, 17, 1135–1145. [Google Scholar] [CrossRef]
  9. Dixit, S.; Fallah, S.; Montanaro, U.; Dianati, M.; Stevens, A.; Mccullough, F.; Mouzakitis, A. Trajectory planning and tracking for autonomous overtaking: State-of-the-art and future prospects. Annu. Rev. Control 2018, 45, 76–86. [Google Scholar] [CrossRef]
  10. Claussmann, L.; Revilloud, M.; Gruyer, D.; Glaser, S. A Review of Motion Planning for Highway Autonomous Driving. IEEE Trans. Intell. Transp. Syst. 2020, 21, 1826–1848. [Google Scholar] [CrossRef]
  11. Gul, F.; Mir, I.; Abualigah, L.; Sumari, P.; Forestiero, A. A Consolidated Review of Path Planning and Optimization Techniques: Technical Perspectives and Future Directions. Electronics 2021, 10, 2250. [Google Scholar] [CrossRef]
  12. Abdallaoui, S.; Aglzim, E.H.; Chaibet, A.; Kribèche, A. Thorough Review Analysis of Safe Control of Autonomous Vehicles: Path Planning and Navigation Techniques. Energies 2022, 15, 1358. [Google Scholar] [CrossRef]
  13. Reda, M.; Onsy, A.; Haikal, A.Y.; Ghanbari, A. Path planning algorithms in the autonomous driving system: A comprehensive review. Robot. Auton. Syst. 2024, 174, 104630. [Google Scholar] [CrossRef]
  14. Betts, J.T. Survey of Numerical Methods for Trajectory Optimization. J. Guid. Control Dyn. 1998, 21, 193–207. [Google Scholar] [CrossRef]
  15. Stano, P.; Montanaro, U.; Tavernini, D.; Tufo, M.; Fiengo, G.; Novella, L.; Sorniotti, A. Model predictive path tracking control for automated road vehicles: A review. Annu. Rev. Control 2023, 55, 194–236. [Google Scholar] [CrossRef]
  16. Norouzi, A.; Heidarifar, H.; Borhan, H.; Shahbakhti, M.; Koch, C.R. Integrating Machine Learning and Model Predictive Control for automotive applications: A review and future directions. Eng. Appl. Artif. Intell. 2023, 120, 105878. [Google Scholar] [CrossRef]
  17. Teng, S.; Hu, X.; Deng, P.; Li, B.; Li, Y.; Ai, Y.; Yang, D.; Li, L.; Xuanyuan, Z.; Zhu, F.; et al. Motion Planning for Autonomous Driving: The State of the Art and Future Perspectives. IEEE Trans. Intell. Veh. 2023, 8, 3692–3711. [Google Scholar] [CrossRef]
  18. Zhu, Z.; Zhao, H. A Survey of Deep RL and IL for Autonomous Driving Policy Learning. IEEE Trans. Intell. Transp. Syst. 2022, 23, 14043–14065. [Google Scholar] [CrossRef]
  19. Cui, C.; Ma, Y.; Cao, X.; Ye, W.; Zhou, Y.; Liang, K.; Chen, J.; Lu, J.; Yang, Z.; Liao, K.D.; et al. A Survey on Multimodal Large Language Models for Autonomous Driving. In Proceedings of the IEEE/CVF Winter Conference on Applications of Computer Vision, Waikoloa, HI, USA, 1–6 January 2024; pp. 958–979. [Google Scholar]
  20. Yi, D.; Su, J.; Hu, L.; Liu, C.; Quddus, M.; Dianati, M.; Chen, W.H. Implicit Personalization in Driving Assistance: State-of-the-Art and Open Issues. IEEE Trans. Intell. Veh. 2020, 5, 397–413. [Google Scholar] [CrossRef]
  21. Liao, X.; Zhao, Z.; Barth, M.J.; Abdelraouf, A.; Gupta, R.; Han, K.; Ma, J.; Wu, G. A Review of Personalization in Driving Behavior: Dataset, Modeling, and Validation. IEEE Trans. Intell. Veh. 2024, 1–22. [Google Scholar] [CrossRef]
  22. Villagra, J.; Milanés, V.; Rastelli, J.P.; Godoy, J.; Onieva, E. Path and speed planning for smooth autonomous navigation. In Proceedings of the IV 2012-IEEE Intelligent Vehicles Symposium, Madrid, Spain, 3–7 June 2012. [Google Scholar]
  23. Bahram, M.; Wolf, A.; Aeberhard, M.; Wollherr, D. A prediction-based reactive driving strategy for highly automated driving function on freeways. In Proceedings of the 2014 IEEE Intelligent Vehicles Symposium Proceedings, Dearborn, MI, USA, 8–11 June 2014; pp. 400–406. [Google Scholar] [CrossRef]
  24. Gu, T.; Dolan, J.M.; Lee, J.W. Runtime-bounded tunable motion planning for autonomous driving. In Proceedings of the 2016 IEEE Intelligent Vehicles Symposium (IV), Gothenburg, Sweden, 19–22 June 2016; pp. 1301–1306. [Google Scholar] [CrossRef]
  25. Rowold, M.; Ögretmen, L.; Kerbl, T.; Lohmann, B. Efficient Spatiotemporal Graph Search for Local Trajectory Planning on Oval Race Tracks. Actuators 2022, 11, 319. [Google Scholar] [CrossRef]
  26. Boroujeni, Z.; Goehring, D.; Ulbrich, F.; Neumann, D.; Rojas, R. Flexible unit A-star trajectory planning for autonomous vehicles on structured road maps. In Proceedings of the 2017 IEEE International Conference on Vehicular Electronics and Safety (ICVES), Vienna, Austria, 27–28 June 2017; pp. 7–12. [Google Scholar] [CrossRef]
  27. Bounini, F.; Gingras, D.; Pollart, H.; Gruyer, D. Modified artificial potential field method for online path planning applications. In Proceedings of the 2017 IEEE Intelligent Vehicles Symposium (IV), Los Angeles, CA, USA, 11–14 June 2017; pp. 180–185. [Google Scholar] [CrossRef]
  28. Ju, C.; Luo, Q.; Yan, X. Path Planning Using an Improved A-star Algorithm. In Proceedings of the 2020 11th International Conference on Prognostics and System Health Management (PHM-2020 Jinan), Jinan, China, 23–25 October 2020; pp. 23–26. [Google Scholar] [CrossRef]
  29. Xin, L.; Kong, Y.; Li, S.E.; Chen, J.; Guan, Y.; Tomizuka, M.; Cheng, B. Enable faster and smoother spatio-temporal trajectory planning for autonomous vehicles in constrained dynamic environment. Proc. Inst. Mech. Eng. Part D J. Automob. Eng. 2021, 235, 1101–1112. [Google Scholar] [CrossRef]
  30. McNaughton, M.; Urmson, C.; Dolan, J.M.; Lee, J.W. Motion planning for autonomous driving with a conformal spatiotemporal lattice. In Proceedings of the 2011 IEEE International Conference on Robotics and Automation, Shanghai, China, 9–13 May 2011; pp. 4889–4895. [Google Scholar] [CrossRef]
  31. Stahl, T.; Wischnewski, A.; Betz, J.; Lienkamp, M. Multilayer Graph-Based Trajectory Planning for Race Vehicles in Dynamic Scenarios. In Proceedings of the 2019 IEEE Intelligent Transportation Systems Conference (ITSC), Auckland, New Zealand, 27–30 October 2019; pp. 3149–3154. [Google Scholar] [CrossRef]
  32. Dolgov, D.; Thrun, S.; Montemerlo, M.; Diebel, J. Practical Search Techniques in Path Planning for Autonomous Driving; American Association for Artificial Intelligence: Washington, DC, USA, 2008; p. 6. [Google Scholar]
  33. Kurzer, K. Path Planning in Unstructured Environments: A Real-Time Hybrid A* Implementation for Fast and Deterministic Path Generation for the KTH Research Concept Vehicle; KTH Royal Institute of Technology: Stockholm, Sweden, 2016. [Google Scholar]
  34. Thoresen, M.; Nielsen, N.H.; Mathiassen, K.; Pettersen, K.Y. Path Planning for UGVs Based on Traversability Hybrid A*. IEEE Robot. Autom. Lett. 2021, 6, 1216–1223. [Google Scholar] [CrossRef]
  35. Hesse, T.; Hess, D.; Sattel, T. Motion Planning for Passenger Vehicles—Force Field Trajectory Optimization for Automated Driving. In Proceedings of the IASTED Technology Conferences/705: ARP/706: RA/707: NANA/728: CompBIO, Cambridge, MA, USA, 1–3 November 2010. [Google Scholar] [CrossRef]
  36. Gochev, K.; Safonova, A.; Likhachev, M. Anytime Tree-Restoring Weighted A* Graph Search. Proc. Int. Symp. Comb. Search 2014, 5, 80–88. [Google Scholar] [CrossRef]
  37. Rezaei, S.; Guivant, J.; Nebot, E. Car-like robot path following in large unstructured environments. In Proceedings of the 2003 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS 2003) (Cat. No.03CH37453), Las Vegas, NV, USA, 27–31 October 2003; Volume 3, pp. 2468–2473. [Google Scholar] [CrossRef]
  38. Koenig, S.; Likhachev, M. D*lite. In Proceedings of the Eighteenth National Conference on Artificial Intelligence, Edmonton, AB, Canada, 28 July–1 August 2002; pp. 476–483. [Google Scholar]
  39. Koenig, S.; Likhachev, M.; Furcy, D. Lifelong Planning A*. Artif. Intell. 2004, 155, 93–146. [Google Scholar] [CrossRef]
  40. Maw, A.A.; Tyan, M.; Lee, J.W. iADA*: Improved Anytime Path Planning and Replanning Algorithm for Autonomous Vehicle. J. Intell. Robot. Syst. 2020, 100, 1005–1013. [Google Scholar] [CrossRef]
  41. Kavraki, L.; Svestka, P.; Latombe, J.C.; Overmars, M. Probabilistic roadmaps for path planning in high-dimensional configuration spaces. IEEE Trans. Robot. Autom. 1996, 12, 566–580. [Google Scholar] [CrossRef]
  42. Karaman, S.; Frazzoli, E. Sampling-based algorithms for optimal motion planning. Int. J. Robot. Res. 2011, 30, 846–894. [Google Scholar] [CrossRef]
  43. Bohlin, R.; Kavraki, L. Path planning using lazy PRM. In Proceedings of the 2000 ICRA, Millennium Conference, IEEE International Conference on Robotics and Automation, Symposia Proceedings (Cat. No.00CH37065), San Francisco, CA, USA, 24–28 April 2000; Volume 1, pp. 521–528. [Google Scholar] [CrossRef]
  44. Lavalle, S.M. Rapidly-Exploring Random Trees: A New Tool for Path Planning; Research Report 9811; Department of Computer Science, Iowa State University: Ames, IA, USA, 1998. [Google Scholar]
  45. Kuffner, J.; LaValle, S. RRT-connect: An efficient approach to single-query path planning. In Proceedings of the 2000 ICRA, Millennium Conference, IEEE International Conference on Robotics and Automation, Symposia Proceedings (Cat. No.00CH37065), San Francisco, CA, USA, 24–28 April 2000; Volume 2, pp. 995–1001. [Google Scholar] [CrossRef]
  46. Wu, B.; Zhang, W.; Chi, X.; Jiang, D.; Yi, Y.; Lu, Y. A Novel AGV Path Planning Approach for Narrow Channels Based on the Bi-RRT Algorithm with a Failure Rate Threshold. Sensors 2023, 23, 7547. [Google Scholar] [CrossRef] [PubMed]
  47. Karaman, S.; Frazzoli, E. Optimal kinodynamic motion planning using incremental sampling-based methods. In Proceedings of the 49th IEEE Conference on Decision and Control (CDC), Atlanta, GA, USA, 15–17 December 2010; pp. 7681–7687. [Google Scholar] [CrossRef]
  48. Gammell, J.D.; Barfoot, T.D.; Srinivasa, S.S. Informed sampling for asymptotically optimal path planning. IEEE Trans. Robot. (T-RO) 2018, 34, 966–984. [Google Scholar] [CrossRef]
  49. Webb, D.J.; Berg, J.v.d. Kinodynamic RRT*: Asymptotically optimal motion planning for robots with linear dynamics. In Proceedings of the 2013 IEEE International Conference on Robotics and Automation, Karlsruhe, Germany, 6–10 May 2013. [Google Scholar] [CrossRef]
  50. Wang, J.; Li, B.; Meng, M.Q.H. Kinematic Constrained Bi-directional RRT with Efficient Branch Pruning for robot path planning. Expert Syst. Appl. 2021, 170, 114541. [Google Scholar] [CrossRef]
  51. Penrose, M. Random Geometric Graphs; Oxford University Press: Oxford, UK, 2003. [Google Scholar] [CrossRef]
  52. Janson, L.; Schmerling, E.; Clark, A.; Pavone, M. Fast marching tree: A fast marching sampling-based method for optimal motion planning in many dimensions. Int. J. Robot. Res. 2015, 34, 883–921. [Google Scholar] [CrossRef] [PubMed]
  53. Gammell, J.D.; Barfoot, T.D.; Srinivasa, S.S. Batch Informed Trees (BIT*): Informed asymptotically optimal anytime search. Int. J. Robot. Res. 2020, 39, 543–567. [Google Scholar] [CrossRef]
  54. Strub, M.P.; Gammell, J.D. Advanced BIT (ABIT): Sampling-Based Planning with Advanced Graph-Search Techniques. In Proceedings of the 2020 IEEE International Conference on Robotics and Automation (ICRA), Paris, France, 31 May–31 August 2020; pp. 130–136. [Google Scholar] [CrossRef]
  55. Xu, P.; Wang, N.; Dai, S.L.; Zuo, L. Motion Planning for Mobile Robot with Modified BIT* and MPC. Appl. Sci. 2021, 11, 426. [Google Scholar] [CrossRef]
  56. Strub, M.P.; Gammell, J.D. Adaptively Informed Trees (AIT*) and Effort Informed Trees (EIT*): Asymmetric bidirectional sampling-based path planning. Int. J. Robot. Res. (IJRR) 2022, 41, 390–417. [Google Scholar] [CrossRef]
  57. Huang, C.; Huang, H.; Hang, P.; Gao, H.; Wu, J.; Huang, Z.; Lv, C. Personalized Trajectory Planning and Control of Lane-Change Maneuvers for Autonomous Driving. IEEE Trans. Veh. Technol. 2021, 70, 5511–5523. [Google Scholar] [CrossRef]
  58. Wang, J.; Wu, S.; Li, H.; Zou, J. Path planning combining improved rapidly-exploring random trees with dynamic window approach in ROS. In Proceedings of the 2018 13th IEEE Conference on Industrial Electronics and Applications (ICIEA), Wuhan, China, 31 May–2 June 2018; pp. 1296–1301. [Google Scholar] [CrossRef]
  59. Rong, J.; Arrigoni, S.; Luan, N.; Braghin, F. Attention-based Sampling Distribution for Motion Planning in Autonomous Driving. In Proceedings of the 2020 39th Chinese Control Conference (CCC), Shenyang, China, 9 September 2020; pp. 5671–5676. [Google Scholar] [CrossRef]
  60. Sussmann, J.; Tang, G. Shortest Paths for the Reeds-Shepp Car: A Worked Out Example of the Use of Geometric Techniques in Nonlinear Optimal Control; SYCON—Rutgers Center for Systems and Control: New Brunswick, NJ, USA, 1991. [Google Scholar]
  61. Giordano, P.R.; Vendittelli, M. Shortest Paths to Obstacles for a Polygonal Dubins Car. IEEE Trans. Robot. 2009, 25, 1184–1191. [Google Scholar] [CrossRef]
  62. Baass, K.G. Use of Clothoid Templates in Highway Design. In Proceedings of the 1982 Roads and Transportation Association of Canada Conference, Halifax, NS, Canada, 16–19 September 1982. [Google Scholar]
  63. Lima, P.F.; Trincavelli, M.; Mårtensson, J.; Wahlberg, B. Clothoid-Based Speed Profiler and Control for Autonomous Driving. In Proceedings of the 2015 IEEE 18th International Conference on Intelligent Transportation Systems, Gran Canaria, Spain, 15–18 September 2015; pp. 2194–2199. [Google Scholar] [CrossRef]
  64. Mouhagir, H.; Talj, R.; Cherfaoui, V.; Aioun, F.; Guillemard, F. Integrating safety distances with trajectory planning by modifying the occupancy grid for autonomous vehicle navigation. In Proceedings of the 2016 IEEE 19th International Conference on Intelligent Transportation Systems (ITSC), Rio de Janeiro, Brazil, 1–4 November 2016; pp. 1114–1119. [Google Scholar] [CrossRef]
  65. Vázquez-Méndez, M.E.; Casal, G. The Clothoid Computation: A Simple and Efficient Numerical Algorithm. J. Surv. Eng. 2016, 142, 04016005. [Google Scholar] [CrossRef]
  66. Gu, T.; Snider, J.; Dolan, J.M.; Lee, J.w. Focused Trajectory Planning for autonomous on-road driving. In Proceedings of the 2013 IEEE Intelligent Vehicles Symposium (IV), Gold Coast, Australia, 23–26 June 2013; pp. 547–552. [Google Scholar] [CrossRef]
  67. Arbitmann, M.; Stählin, U.; Schorn, M.; Isermann, R. Method and device for performing a collision avoidance maneuver. U.S. Patent US8209090B2, 26 June 2012. [Google Scholar]
  68. Xu, W.; Wei, J.; Dolan, J.M.; Zhao, H.; Zha, H. A real-time motion planner with trajectory optimization for autonomous vehicles. In Proceedings of the 2012 IEEE International Conference on Robotics and Automation, Saint Paul, MN, USA, 14–18 May 2012; pp. 2061–2067. [Google Scholar] [CrossRef]
  69. Tehrani, H.; Huy Do, Q.; Egawa, M.; Muto, K.; Yoneda, K.; Mita, S. General behavior and motion model for automated lane change. In Proceedings of the 2015 IEEE Intelligent Vehicles Symposium (IV), Seoul, Republic of Korea, 28 June–1 July 2015; pp. 1154–1159. [Google Scholar] [CrossRef]
  70. Schubert, R.; Scheunert, U.; Wanielik, G. Planning feasible vehicle manoeuvres on highways. IET Intell. Transp. Syst. 2008, 2, 211–218. [Google Scholar] [CrossRef]
  71. Cao, H.; Zhao, S.; Song, X.; Bao, S.; Li, M.; Huang, Z.; Hu, C. An optimal hierarchical framework of the trajectory following by convex optimisation for highly automated driving vehicles. Veh. Syst. Dyn. 2018, 57, 1287–1317. [Google Scholar] [CrossRef]
  72. Mellinger, D.; Kumar, V. Minimum snap trajectory generation and control for quadrotors. In Proceedings of the 2011 IEEE International Conference on Robotics and Automation, Shanghai, China, 9–13 May 2011; pp. 2520–2525. [Google Scholar] [CrossRef]
  73. Heilmeier, A.; Wischnewski, A.; Hermansdorfer, L.; Betz, J.; Lienkamp, M.; Lohmann, B. Minimum curvature trajectory planning and control for an autonomous race car. Veh. Syst. Dyn. 2020, 58, 1497–1527. [Google Scholar] [CrossRef]
  74. Artuñedo, A.; Villagra, J.; Godoy, J. Real-Time Motion Planning Approach for Automated Driving in Urban Environments. IEEE Access 2019, 7, 180039–180053. [Google Scholar] [CrossRef]
  75. Zhou, B.; Gao, F.; Wang, L.; Liu, C.; Shen, S. Robust and Efficient Quadrotor Trajectory Generation for Fast Autonomous Flight. IEEE Robot. Autom. Lett. 2019, 4, 3529–3536. [Google Scholar] [CrossRef]
  76. Li, X.; Sun, Z.; Cao, D.; Liu, D.; He, H. Development of a new integrated local trajectory planning and tracking control framework for autonomous ground vehicles. Mech. Syst. Signal Process. 2017, 87, 118–137. [Google Scholar] [CrossRef]
  77. Zhou, J.; Zheng, H.; Wang, J.; Wang, Y.; Zhang, B.; Shao, Q. Multiobjective Optimization of Lane-Changing Strategy for Intelligent Vehicles in Complex Driving Environments. IEEE Trans. Veh. Technol. 2020, 69, 1291–1308. [Google Scholar] [CrossRef]
  78. Knepper, R.; Kelly, A. High Performance State Lattice Planning Using Heuristic Look-Up Tables. In Proceedings of the 2006 IEEE/RSJ International Conference on Intelligent Robots and Systems, Beijing, China, 9–15 October 2006; pp. 3375–3380. [Google Scholar] [CrossRef]
  79. Werling, M.; Ziegler, J.; Kammel, S.; Thrun, S. Optimal trajectory generation for dynamic street scenarios in a Frenét Frame. In Proceedings of the 2010 IEEE International Conference on Robotics and Automation, Anchorage, AK, USA, 3–7 May 2010; pp. 987–993. [Google Scholar] [CrossRef]
  80. Chen, J.; Zhan, W.; Tomizuka, M. Autonomous Driving Motion Planning with Constrained Iterative LQR. IEEE Trans. Intell. Veh. 2019, 4, 244–254. [Google Scholar] [CrossRef]
  81. Cao, K.; Cao, M.; Yuan, S.; Xie, L. DIRECT: A Differential Dynamic Programming Based Framework for Trajectory Generation. IEEE Robot. Autom. Lett. 2022, 7, 2439–2446. [Google Scholar] [CrossRef]
  82. 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]
  83. Zhang, W.; Wang, Z.; Drugge, L.; Nybacka, M. Evaluating Model Predictive Path Following and Yaw Stability Controllers for Over-Actuated Autonomous Electric Vehicles. IEEE Trans. Veh. Technol. 2020, 69, 12807–12821. [Google Scholar] [CrossRef]
  84. Wang, Z.; Zha, J.; Wang, J. Flatness-based Model Predictive Control for Autonomous Vehicle Trajectory Tracking. In Proceedings of the 2019 IEEE Intelligent Transportation Systems Conference (ITSC), Auckland, New Zealand, 27–30 October 2019; pp. 4146–4151. [Google Scholar] [CrossRef]
  85. Xiang, C.; Peng, H.; Wang, W.; Li, L.; An, Q.; Cheng, S. Path tracking coordinated control strategy for autonomous four in-wheel-motor independent-drive vehicles with consideration of lateral stability. Proc. Inst. Mech. Eng. Part D J. Automob. Eng. 2021, 235, 1023–1036. [Google Scholar] [CrossRef]
  86. Morato, M.M.; Normey-Rico, J.E.; Sename, O. Model predictive control design for linear parameter varying systems: A survey. Annu. Rev. Control 2020, 49, 64–80. [Google Scholar] [CrossRef]
  87. Zhang, K.; Sprinkle, J.; Sanfelice, R.G. Computationally aware control of autonomous vehicles: A hybrid model predictive control approach. Auton. Robot. 2015, 39, 503–517. [Google Scholar] [CrossRef]
  88. Spielberg, N.A.; Brown, M.; Gerdes, J.C. Neural Network Model Predictive Motion Control Applied to Automated Driving with Unknown Friction. IEEE Trans. Control Syst. Technol. 2022, 30, 1934–1945. [Google Scholar] [CrossRef]
  89. Zuo, Z.; Yang, X.; Zhang, Z.; Wang, Y. Lane-Associated MPC Path Planning for Autonomous Vehicles. In Proceedings of the 2019 Chinese Control Conference (CCC), Guangzhou, China, 27–30 July 2019; pp. 6627–6632. [Google Scholar] [CrossRef]
  90. Huang, C.; Lv, C.; Hang, P.; Xing, Y. Toward Safe and Personalized Autonomous Driving: Decision-Making and Motion Control with DPF and CDT Techniques. IEEE/ASME Trans. Mechatron. 2021, 26, 611–620. [Google Scholar] [CrossRef]
  91. 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]
  92. Rokonuzzaman, M.; Mohajer, N.; Nahavandi, S.; Mohamed, S. Learning-based Model Predictive Control for Path Tracking Control of Autonomous Vehicle. In Proceedings of the 2020 IEEE International Conference on Systems, Man, and Cybernetics (SMC), Toronto, ON, Canada, 11–14 October 2020; pp. 2913–2918. [Google Scholar] [CrossRef]
  93. Chen, J.; Zhan, W.; Tomizuka, M. Constrained iterative LQR for on-road autonomous driving motion planning. In Proceedings of the 2017 IEEE 20th International Conference on Intelligent Transportation Systems (ITSC), Yokohama, Japan, 16–19 October 2017; pp. 1–7. [Google Scholar] [CrossRef]
  94. Ma, J.; Cheng, Z.; Zhang, X.; Tomizuka, M.; Lee, T.H. Alternating Direction Method of Multipliers for Constrained Iterative LQR in Autonomous Driving. IEEE Trans. Intell. Transp. Syst. 2022, 23, 23031–23042. [Google Scholar] [CrossRef]
  95. Li, W.; Todorov, E. Iterative Linear Quadratic Regulator Design for Nonlinear Biological Movement Systems. In Proceedings of the First International Conference on Informatics in Control, Automation and Robotics, Setúbal, Portugal, 25–28 August 2004; Volume 2, pp. 222–229. [Google Scholar] [CrossRef]
  96. Chen, Y.; Rosolia, U.; Ubellacker, W.; Csomay-Shanklin, N.; Ames, A.D. Interactive Multi-Modal Motion Planning with Branch Model Predictive Control. IEEE Robot. Autom. Lett. 2022, 7, 5365–5372. [Google Scholar] [CrossRef]
  97. Da, F. Comprehensive Reactive Safety: No Need For A Trajectory If You Have A Strategy. In Proceedings of the 2022 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Kyoto, Japan, 23–27 October 2022; pp. 2903–2910. [Google Scholar] [CrossRef]
  98. Li, T.; Zhang, L.; Liu, S.; Shen, S. MARC: Multipolicy and Risk-Aware Contingency Planning for Autonomous Driving. IEEE Robot. Autom. Lett. 2023, 8, 6587–6594. [Google Scholar] [CrossRef]
  99. Hardy, J.; Campbell, M. Contingency Planning Over Probabilistic Obstacle Predictions for Autonomous Road Vehicles. IEEE Trans. Robot. 2013, 29, 913–929. [Google Scholar] [CrossRef]
  100. Kelly, M. An Introduction to Trajectory Optimization: How to Do Your Own Direct Collocation. SIAM Rev. 2017, 59, 849–904. [Google Scholar] [CrossRef]
  101. Fassbender, D.; Heinrich, B.C.; Luettel, T.; Wuensche, H.J. An optimization approach to trajectory generation for autonomous vehicle following. In Proceedings of the 2017 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Vancouver, BC, Canada, 24–28 September 2017; pp. 3675–3680. [Google Scholar] [CrossRef]
  102. Wang, Z.; Zhou, X.; Xu, C.; Gao, F. Geometrically Constrained Trajectory Optimization for Multicopters. IEEE Trans. Robot. 2022, 38, 3259–3278. [Google Scholar] [CrossRef]
  103. Han, Z.; Wu, Y.; Li, T.; Zhang, L.; Pei, L.; Xu, L.; Li, C.; Ma, C.; Xu, C.; Shen, S.; et al. An Efficient Spatial-Temporal Trajectory Planner for Autonomous Vehicles in Unstructured Environments. IEEE Trans. Intell. Transp. Syst. 2023, 25, 1797–1814. [Google Scholar] [CrossRef]
  104. Meng, Y.; Wu, Y.; Gu, Q.; Liu, L. A Decoupled Trajectory Planning Framework Based on the Integration of Lattice Searching and Convex Optimization. IEEE Access 2019, 7, 130530–130551. [Google Scholar] [CrossRef]
  105. Zhou, J.; He, R.; Wang, Y.; Jiang, S.; Zhu, Z.; Hu, J.; Miao, J.; Luo, Q. Autonomous Driving Trajectory Optimization with Dual-Loop Iterative Anchoring Path Smoothing and Piecewise-Jerk Speed Optimization. IEEE Robot. Autom. Lett. 2021, 6, 439–446. [Google Scholar] [CrossRef]
  106. Rösmann, C.; Hoffmann, F.; Bertram, T. Kinodynamic trajectory optimization and control for car-like robots. In Proceedings of the 2017 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Vancouver, BC, Canada, 24–28 September 2017; pp. 5681–5686. [Google Scholar] [CrossRef]
  107. Fu, Z.; Xiong, L.; Qian, Z.; Leng, B.; Zeng, D.; Huang, Y. Model Predictive Trajectory Optimization and Tracking in Highly Constrained Environments. Int. J. Automot. Technol. 2022, 23, 927–938. [Google Scholar] [CrossRef]
  108. Lim, W.; Lee, S.; Sunwoo, M.; Jo, K. Hierarchical Trajectory Planning of an Autonomous Car Based on the Integration of a Sampling and an Optimization Method. IEEE Trans. Intell. Transp. Syst. 2018, 19, 613–626. [Google Scholar] [CrossRef]
  109. Chai, R.; Tsourdos, A.; Chai, S.; Xia, Y.; Savvaris, A.; Chen, C.L.P. Multiphase Overtaking Maneuver Planning for Autonomous Ground Vehicles Via a Desensitized Trajectory Optimization Approach. IEEE Trans. Ind. Inform. 2023, 19, 74–87. [Google Scholar] [CrossRef]
  110. Zhu, Z.; Zhao, H. Multi-Task Conditional Imitation Learning for Autonomous Navigation at Crowded Intersections. arXiv 2022, arXiv:2202.10124. [Google Scholar] [CrossRef]
  111. Hoque, R.; Balakrishna, A.; Novoseller, E.; Wilcox, A.; Brown, D.S.; Goldberg, K. ThriftyDAgger: Budget-Aware Novelty and Risk Gating for Interactive Imitation Learning. arXiv 2021, arXiv:2109.08273. [Google Scholar] [CrossRef]
  112. Yan, C.; Qin, J.; Liu, Q.; Ma, Q.; Kang, Y. Mapless Navigation with Safety-Enhanced Imitation Learning. IEEE Trans. Ind. Electron. 2023, 70, 7073–7081. [Google Scholar] [CrossRef]
  113. Phan-Minh, T.; Howington, F.; Chu, T.S.; Lee, S.U.; Tomov, M.S.; Li, N.; Dicle, C.; Findler, S.; Suarez-Ruiz, F.; Beaudoin, R.; et al. Driving in Real Life with Inverse Reinforcement Learning. arXiv 2022, arXiv:2206.03004. [Google Scholar] [CrossRef]
  114. Brown, D.; Niekum, S. Efficient Probabilistic Performance Bounds for Inverse Reinforcement Learning. In Proceedings of the AAAI Conference on Artificial Intelligence, New Orleans, LA, USA, 2–7 February 2018; Volume 32. [Google Scholar] [CrossRef]
  115. Ho, J.; Ermon, S. Generative Adversarial Imitation Learning. In Proceedings of the Advances in Neural Information Processing Systems, Barcelona, Spain, 5–10 December 2016; Volume 29. [Google Scholar]
  116. Ronecker, M.P.; Zhu, Y. Deep Q-Network Based Decision Making for Autonomous Driving. In Proceedings of the 2019 3rd International Conference on Robotics and Automation Sciences (ICRAS), Wuhan, China, 1–3 June 2019; pp. 154–160. [Google Scholar] [CrossRef]
  117. Kaushik, M.; Singhania, N.; Singamaneni, P.; Krishna, K.M. Parameter Sharing Reinforcement Learning Architecture for Multi Agent Driving. In Proceedings of the 2019 4th International Conference on Advances in Robotics, Chennai, India, 2–6 July 2019; pp. 1–7. [Google Scholar] [CrossRef]
  118. Wu, Y.; Liao, S.; Liu, X.; Li, Z.; Lu, R. Deep Reinforcement Learning on Autonomous Driving Policy with Auxiliary Critic Network. IEEE Trans. Neural Netw. Learn. Syst. 2023, 34, 3680–3690. [Google Scholar] [CrossRef] [PubMed]
  119. Ye, F.; Cheng, X.; Wang, P.; Chan, C.Y.; Zhang, J. Automated Lane Change Strategy using Proximal Policy Optimization-based Deep Reinforcement Learning. In Proceedings of the 2020 IEEE Intelligent Vehicles Symposium (IV), Las Vegas, NV, USA, 19 October–13 November 2020; pp. 1746–1752. [Google Scholar] [CrossRef]
  120. Wu, J.; Huang, Z.; Huang, W.; Lv, C. Prioritized Experience-Based Reinforcement Learning with Human Guidance for Autonomous Driving. IEEE Trans. Neural Netw. Learn. Syst. 2022, 35, 855–869. [Google Scholar] [CrossRef]
  121. Liang, X.; Wang, T.; Yang, L.; Xing, E. CIRL: Controllable Imitative Reinforcement Learning for Vision-based Self-driving. In Proceedings of the European Conference on Computer vision (ECCV), Munich, Germany, 8–14 September 2018; pp. 584–599. [Google Scholar]
  122. Fraichard, T. Trajectory planning in a dynamic workspace: A ’state-time space’ approach. Adv. Robot. 1998, 13, 75–94. [Google Scholar] [CrossRef]
  123. Morsali, M.; Frisk, E.; Åslund, J. Spatio-Temporal Planning in Multi-Vehicle Scenarios for Autonomous Vehicle Using Support Vector Machines. IEEE Trans. Intell. Veh. 2021, 6, 611–621. [Google Scholar] [CrossRef]
  124. He, S.; Zeng, J.; Sreenath, K. Autonomous Racing with Multiple Vehicles using a Parallelized Optimization with Safety Guarantee using Control Barrier Functions. In Proceedings of the 2022 International Conference on Robotics and Automation (ICRA), Philadelphia, PA, USA, 23–27 May 2022; pp. 3444–3451. [Google Scholar] [CrossRef]
  125. Guo, Y.; Yao, D.; Li, B.; He, Z.; Gao, H.; Li, L. Trajectory Planning for an Autonomous Vehicle in Spatially Constrained Environments. IEEE Trans. Intell. Transp. Syst. 2022, 23, 18326–18336. [Google Scholar] [CrossRef]
  126. Zhang, Y.; Sun, H.; Zhou, J.; Pan, J.; Hu, J.; Miao, J. Optimal Vehicle Path Planning Using Quadratic Optimization for Baidu Apollo Open Platform. In Proceedings of the 2020 IEEE Intelligent Vehicles Symposium (IV), Las Vegas, NV, USA, 19 October–13 November 2020; pp. 978–984. [Google Scholar] [CrossRef]
  127. Sun, J. Occupancy-assisted Surround-view Images 3D Object Detection. IEEE Access 2024, 99, 1. [Google Scholar] [CrossRef]
  128. Arun, A.; Haque, M.M.; Washington, S.; Sayed, T.; Mannering, F. A systematic review of traffic conflict-based safety measures with a focus on application context. Anal. Methods Accid. Res. 2021, 32, 100185. [Google Scholar] [CrossRef]
  129. Wang, C.; Xie, Y.; Huang, H.; Liu, P. A review of surrogate safety measures and their applications in connected and automated vehicles safety modeling. Accid. Anal. Prev. 2021, 157, 106157. [Google Scholar] [CrossRef]
  130. Yu, L.; Wang, R. Researches on Adaptive Cruise Control system: A state of the art review. Proc. Inst. Mech. Eng. Part D J. Automob. Eng. 2022, 236, 211–240. [Google Scholar] [CrossRef]
  131. Gao, B.; Cai, K.; Qu, T.; Hu, Y.; Chen, H. Personalized Adaptive Cruise Control Based on Online Driving Style Recognition Technology and Model Predictive Control. IEEE Trans. Veh. Technol. 2020, 69, 12482–12496. [Google Scholar] [CrossRef]
  132. Zhu, B.; Jiang, Y.; Zhao, J.; He, R.; Bian, N.; Deng, W. Typical-driving-style-oriented Personalized Adaptive Cruise Control design based on human driving data. Transp. Res. Part C Emerg. Technol. 2019, 100, 274–288. [Google Scholar] [CrossRef]
  133. Kondoh, T.; Yamamura, T.; Kitazaki, S.; Kuge, N.; Boer, E.R. Identification of Visual Cues and Quantification of Drivers’ Perception of Proximity Risk to the Lead Vehicle in Car-Following Situations. J. Mech. Syst. Transp. Logist. 2008, 1, 170–180. [Google Scholar] [CrossRef]
  134. Kondoh, T.; Furuyama, N.; Hirose, T.; Sawada, T. Direct Evidence of the Inverse of TTC Hypothesis for Driver’s Perception in Car-Closing Situations. Int. J. Automot. Eng. 2014, 5, 121–128. [Google Scholar] [CrossRef] [PubMed]
  135. Siebert, F.W.; Oehl, M.; Pfister, H.R. The influence of time headway on subjective driver states in adaptive cruise control. Transp. Res. Part F Traffic Psychol. Behav. 2014, 25, 65–73. [Google Scholar] [CrossRef]
  136. Siebert, F.W.; Oehl, M.; Bersch, F.; Pfister, H.R. The exact determination of subjective risk and comfort thresholds in car following. Transp. Res. Part F Traffic Psychol. Behav. 2017, 46, 1–13. [Google Scholar] [CrossRef]
  137. Zhou, H.; Itoh, M. How does a driver perceive risk when making decision of lane-changing? IFAC-PapersOnLine 2016, 49, 60–65. [Google Scholar] [CrossRef]
  138. Boer, E.R. Satisficing Curve Negotiation: Explaining Drivers’ Situated Lateral Position Variability. IFAC-PapersOnLine 2016, 49, 183–188. [Google Scholar] [CrossRef]
  139. Guo, Z.; Chen, H.; Xia, T.; Ran, W.; Yosuke, N.; Wang, J. Study on Quantification of Drivers Subjective Risk Perception in Curve Driving Condition. Qiche Gongcheng/Automot. Eng. 2022, 44, 1447–1455. [Google Scholar] [CrossRef]
  140. Lopez, V.G.; Lewis, F.L.; Liu, M.; Wan, Y.; Nageshrao, S.; Filev, D. Game-Theoretic Lane-Changing Decision Making and Payoff Learning for Autonomous Vehicles. IEEE Trans. Veh. Technol. 2022, 71, 3609–3620. [Google Scholar] [CrossRef]
  141. Liu, M.; Wan, Y.; Lewis, F.L.; Nageshrao, S.; Filev, D. A Three-Level Game-Theoretic Decision-Making Framework for Autonomous Vehicles. IEEE Trans. Intell. Transp. Syst. 2022, 23, 20298–20308. [Google Scholar] [CrossRef]
  142. Talebpour, A.; Mahmassani, H.S.; Hamdar, S.H. Modeling lane-changing behavior in a connected environment: A game theory approach. Transp. Res. Part C Emerg. Technol. 2015, 59, 216–232. [Google Scholar] [CrossRef]
  143. Ali, Y.; Zheng, Z.; Haque, M.M.; Yildirimoglu, M.; Washington, S. CLACD: A complete LAne-Changing decision modeling framework for the connected and traditional environments. Transp. Res. Part C Emerg. Technol. 2021, 128, 103162. [Google Scholar] [CrossRef]
  144. Mullakkal-Babu, F.A.; Wang, M.; He, X.; van Arem, B.; Happee, R. Probabilistic field approach for motorway driving risk assessment. Transp. Res. Part C Emerg. Technol. 2020, 118, 102716. [Google Scholar] [CrossRef]
  145. Lu, C.; He, X.; van Lint, H.; Tu, H.; Happee, R.; Wang, M. Performance evaluation of surrogate measures of safety with naturalistic driving data. Accid. Anal. Prev. 2021, 162, 106403. [Google Scholar] [CrossRef] [PubMed]
  146. Li, G.; Yang, Y.; Zhang, T.; Qu, X.; Cao, D.; Cheng, B.; Li, K. Risk assessment based collision avoidance decision-making for autonomous vehicles in multi-scenarios. Transp. Res. Part C Emerg. Technol. 2021, 122, 102820. [Google Scholar] [CrossRef]
  147. Guo, H.; Xie, K.; Keyvan-Ekbatani, M. Modeling driver’s evasive behavior during safety–critical lane changes: Two-dimensional time-to-collision and deep reinforcement learning. Accid. Anal. Prev. 2023, 186, 107063. [Google Scholar] [CrossRef] [PubMed]
  148. Shalev-Shwartz, S.; Shammah, S.; Shashua, A. On a Formal Model of Safe and Scalable Self-driving Cars. arXiv 2018, arXiv:1708.06374. [Google Scholar] [CrossRef]
  149. Gassmann, B.; Pasch, F.; Oboril, F.; Scholl, K.U. Integration of Formal Safety Models on System Level Using the Example of Responsibility Sensitive Safety and CARLA Driving Simulator. In Proceedings of the Computer Safety, Reliability, and Security. SAFECOMP 2020 Workshops, Lisbon, Portugal, 15 September 2020; pp. 358–369. [Google Scholar] [CrossRef]
  150. Nistér, D.; Lee, H.L.; Ng, J.; Wang, Y. The Safety Force Field. 2019. Available online: https://www.nvidia.com/content/dam/en-zz/Solutions/self-driving-cars/safety-force-field/the-safety-force-field.pdf (accessed on 30 June 2024).
  151. Suk, H.; Kim, T.; Park, H.; Yadav, P.; Lee, J.; Kim, S. Rationale-aware Autonomous Driving Policy utilizing Safety Force Field implemented on CARLA Simulator. arXiv 2022, arXiv:2211.10237. [Google Scholar]
  152. Pek, C.; Manzinger, S.; Koschi, M.; Althoff, M. Using online verification to prevent autonomous vehicles from causing accidents. Nat. Mach. Intell. 2020, 2, 518–528. [Google Scholar] [CrossRef]
  153. Chen, C.; Liu, X.; Chen, H.H.; Li, M.; Zhao, L. A Rear-End Collision Risk Evaluation and Control Scheme Using a Bayesian Network Model. IEEE Trans. Intell. Transp. Syst. 2019, 20, 264–284. [Google Scholar] [CrossRef]
  154. Gao, Z.; Bao, M.; Cui, T.; Shi, F.; Chen, X.; Wen, W.; Gao, F.; Zhao, R. Collision Risk Assessment for Intelligent Vehicles Considering Multi-Dimensional Uncertainties. IEEE Access 2024, 12, 57780–57795. [Google Scholar] [CrossRef]
  155. Huang, Y.; Du, J.; Yang, Z.; Zhou, Z.; Zhang, L.; Chen, H. A Survey on Trajectory-Prediction Methods for Autonomous Driving. IEEE Trans. Intell. Veh. 2022, 7, 652–674. [Google Scholar] [CrossRef]
  156. Wang, H.; Lu, B.; Li, J.; Liu, T.; Xing, Y.; Lv, C.; Cao, D.; Li, J.; Zhang, J.; Hashemi, E. Risk Assessment and Mitigation in Local Path Planning for Autonomous Vehicles with LSTM Based Predictive Model. IEEE Trans. Autom. Sci. Eng. 2022, 19, 2738–2749. [Google Scholar] [CrossRef]
  157. Rahmani, S.; Baghbani, A.; Bouguila, N.; Patterson, Z. Graph Neural Networks for Intelligent Transportation Systems: A Survey. IEEE Trans. Intell. Transp. Syst. 2023, 24, 8846–8885. [Google Scholar] [CrossRef]
  158. Zhang, Y.; Chen, H.; Waslander, S.L.; Gong, J.; Xiong, G.; Yang, T.; Liu, K. Hybrid Trajectory Planning for Autonomous Driving in Highly Constrained Environments. IEEE Access 2018, 6, 32800–32819. [Google Scholar] [CrossRef]
  159. Yang, D.; Zheng, S.; Wen, C.; Jin, P.J.; Ran, B. A dynamic lane-changing trajectory planning model for automated vehicles. Transp. Res. Part C Emerg. Technol. 2018, 95, 228–247. [Google Scholar] [CrossRef]
  160. Tian, X.; Jiang, T.; Yun, L.; Mao, Y.; Yang, H.; Wang, Y.; Wang, Y.; Zhao, H. Occ3D: A Large-Scale 3D Occupancy Prediction Benchmark for Autonomous Driving. Adv. Neural Inf. Process. Syst. 2023, 36, 64318–64330. [Google Scholar]
  161. Huang, Y.; Zheng, W.; Zhang, Y.; Zhou, J.; Lu, J. Tri-Perspective View for Vision-Based 3D Semantic Occupancy Prediction. In Proceedings of the IEEE/CVF Conference on Computer Vision and Pattern Recognition, Vancouver, BC, Canada, 17–24 June 2023; pp. 9223–9232. [Google Scholar]
  162. Orzechowski, P.F.; Li, K.; Lauer, M. Towards Responsibility-Sensitive Safety of Automated Vehicles with Reachable Set Analysis. In Proceedings of the 2019 IEEE International Conference on Connected Vehicles and Expo (ICCVE), Graz, Austria, 4–8 November 2019; pp. 1–6. [Google Scholar] [CrossRef]
  163. Manzinger, S.; Pek, C.; Althoff, M. Using Reachable Sets for Trajectory Planning of Automated Vehicles. IEEE Trans. Intell. Veh. 2021, 6, 232–248. [Google Scholar] [CrossRef]
  164. Koschi, M.; Althoff, M. SPOT: A tool for set-based prediction of traffic participants. In Proceedings of the 2017 IEEE Intelligent Vehicles Symposium (IV), Los Angeles, CA, USA, 11–14 June 2017; pp. 1686–1693. [Google Scholar] [CrossRef]
  165. Wang, L.; Lopez, C.F.; Stiller, C. Generating Efficient Behaviour with Predictive Visibility Risk for Scenarios with Occlusions. In Proceedings of the 2020 IEEE 23rd International Conference on Intelligent Transportation Systems (ITSC), Rhodes, Greece, 20–23 September 2020; pp. 1–7. [Google Scholar] [CrossRef]
  166. Lee, S.; Lim, W.; Sunwoo, M.; Jo, K. Limited Visibility Aware Motion Planning for Autonomous Valet Parking Using Reachable Set Estimation. Sensors 2021, 21, 1520. [Google Scholar] [CrossRef] [PubMed]
  167. Sontges, S.; Althoff, M. Computing possible driving corridors for automated vehicles. In Proceedings of the 2017 IEEE Intelligent Vehicles Symposium (IV), Los Angeles, CA, USA, 11–14 June 2017; pp. 160–166. [Google Scholar] [CrossRef]
  168. Jiang, J.; Ren, Y.; Guan, Y.; Eben Li, S.; Yin, Y.; Yu, D.; Jin, X. Integrated decision and control at multi-lane intersections with mixed traffic flow. J. Phys. Conf. Ser. 2022, 2234, 012015. [Google Scholar] [CrossRef]
  169. Lu, B.; Li, G.; Yu, H.; Wang, H.; Guo, J.; Cao, D.; He, H. Adaptive Potential Field-Based Path Planning for Complex Autonomous Driving Scenarios. IEEE Access 2020, 8, 225294–225305. [Google Scholar] [CrossRef]
  170. Wahid, N.; Zamzuri, H.; Abdul Rahman, M.A.; Kuroda, S.; Raksincharoensak, P. Study on potential field based motion planning and control for automated vehicle collision avoidance systems. In Proceedings of the 2017 IEEE International Conference on Mechatronics (ICM), Churchill, Australia, 13–15 February 2017; pp. 208–213. [Google Scholar] [CrossRef]
  171. Wang, J.; Wu, J.; Li, Y. The Driving Safety Field Based on Driver–Vehicle–Road Interactions. IEEE Trans. Intell. Transp. Syst. 2015, 16, 2203–2214. [Google Scholar] [CrossRef]
  172. Wang, P.; Gao, S.; Li, L.; Sun, B.; Cheng, S. Obstacle Avoidance Path Planning Design for Autonomous Driving Vehicles Based on an Improved Artificial Potential Field Algorithm. Energies 2019, 12, 2342. [Google Scholar] [CrossRef]
  173. Kolekar, S.; de Winter, J.; Abbink, D. Human-like driving behaviour emerges from a risk-based driver model. Nat. Commun. 2020, 11, 4850. [Google Scholar] [CrossRef] [PubMed]
  174. Kolekar, S.; Petermeijer, B.; Boer, E.; de Winter, J.; Abbink, D. A risk field-based metric correlates with driver’s perceived risk in manual and automated driving: A test-track study. Transp. Res. Part C Emerg. Technol. 2021, 133, 103428. [Google Scholar] [CrossRef]
  175. Xia, T.; Chen, H.; Yang, J.; Guo, Z. Geometric field model of driver’s perceived risk for safe and human-like trajectory planning. Transp. Res. Part C Emerg. Technol. 2024, 159, 104470. [Google Scholar] [CrossRef]
  176. Zhang, Q.; Zhang, T.; Ma, L. Human acceptance of autonomous vehicles: Research status and prospects. Int. J. Ind. Ergon. 2023, 95, 103458. [Google Scholar] [CrossRef]
  177. Choi, J.K.; Ji, Y.G. Investigating the Importance of Trust on Adopting an Autonomous Vehicle. Int. J. Hum.—Comput. Interact. 2015, 31, 692–702. [Google Scholar] [CrossRef]
  178. Robert Bosch GmbH. Personalized Driving Experience. 2024. Available online: https://www.bosch-mobility.com/en/mobility-topics/driving-experience/ (accessed on 20 July 2024).
  179. Lefèvre, S.; Carvalho, A.; Gao, Y.; Tseng, H.E.; Borrelli, F. Driver models for personalised driving assistance. Veh. Syst. Dyn. 2015, 53, 1705–1720. [Google Scholar] [CrossRef]
  180. Wang, W.; Xi, J.; Zhao, D. Learning and Inferring a Driver’s Braking Action in Car-Following Scenarios. IEEE Trans. Veh. Technol. 2018, 67, 3887–3899. [Google Scholar] [CrossRef]
  181. Orth, D.; Kolossa, D.; Paja, M.S.; Schaller, K.; Pech, A.; Heckmann, M. A maximum likelihood method for driver-specific critical-gap estimation. In Proceedings of the 2017 IEEE Intelligent Vehicles Symposium (IV), Los Angeles, CA, USA, 11–14 June 2017; pp. 553–558. [Google Scholar] [CrossRef]
  182. Wang, J.; Zhang, L.; Zhang, D.; Li, K. An Adaptive Longitudinal Driving Assistance System Based on Driver Characteristics. IEEE Trans. Intell. Transp. Syst. 2013, 14, 1–12. [Google Scholar] [CrossRef]
  183. Okuda, H.; Harada, K.; Suzuki, T.; Saigo, S.; Inoue, S. Design of automated merging control by minimizing decision entropy of drivers on main lane. In Proceedings of the 2017 IEEE Intelligent Vehicles Symposium (IV), Los Angeles, CA, USA, 11–14 June 2017; pp. 640–646. [Google Scholar] [CrossRef]
  184. Best, M.C. Real-time characterisation of driver steering behaviour. Veh. Syst. Dyn. 2019, 57, 64–85. [Google Scholar] [CrossRef]
  185. Chu, H.; Zhuang, H.; Wang, W.; Na, X.; Guo, L.; Zhang, J.; Gao, B.; Chen, H. A Review of Driving Style Recognition Methods From Short-Term and Long-Term Perspectives. IEEE Trans. Intell. Veh. 2023, 8, 4599–4612. [Google Scholar] [CrossRef]
  186. Chen, Y.; Wang, K.; Lu, J.J. Feature selection for driving style and skill clustering using naturalistic driving data and driving behavior questionnaire. Accid. Anal. Prev. 2023, 185, 107022. [Google Scholar] [CrossRef] [PubMed]
  187. Yusof, N.M.; Karjanto, J.; Terken, J.; Delbressine, F.; Hassan, M.Z.; Rauterberg, M. The Exploration of Autonomous Vehicle Driving Styles: Preferred Longitudinal, Lateral, and Vertical Accelerations. In Proceedings of the 8th International Conference on Automotive User Interfaces and Interactive Vehicular Applications, Ann Arbor, MI, USA, 24–26 October 2016; pp. 245–252. [Google Scholar] [CrossRef]
  188. Basu, C.; Yang, Q.; Hungerman, D.; Singhal, M.; Dragan, A.D. Do You Want Your Autonomous Car To Drive Like You? In Proceedings of the 2017 ACM/IEEE International Conference on Human-Robot Interaction, Vienna, Austria, 6–9 March 2017; pp. 417–425. [Google Scholar] [CrossRef]
  189. Bellem, H.; Thiel, B.; Schrauf, M.; Krems, J.F. Comfort in automated driving: An analysis of preferences for different automated driving styles and their dependence on personality traits. Transp. Res. Part F Traffic Psychol. Behav. 2018, 55, 90–100. [Google Scholar] [CrossRef]
  190. Delmas, M.; Camps, V.; Lemercier, C. Personalizing automated driving speed to enhance user experience and performance in intermediate-level automated driving. Accid. Anal. Prev. 2024, 199, 107512. [Google Scholar] [CrossRef]
  191. Wilson, A.; Fern, A.; Tadepalli, P. A Bayesian Approach for Policy Learning from Trajectory Preference Queries. In Proceedings of the Advances in Neural Information Processing Systems, Lake Tahoe, CA, USA, 3–6 December 2012; Volume 25. [Google Scholar]
  192. Tucker, M.; Novoseller, E.; Kann, C.; Sui, Y.; Yue, Y.; Burdick, J.W.; Ames, A.D. Preference-Based Learning for Exoskeleton Gait Optimization. In Proceedings of the 2020 IEEE International Conference on Robotics and Automation (ICRA), Paris, France, 31 May–31 August 2020; pp. 2351–2357. [Google Scholar] [CrossRef]
  193. Bıyık, E.; Palan, M.; Landolfi, N.C.; Losey, D.P.; Sadigh, D. Asking Easy Questions: A User-Friendly Approach to Active Reward Learning. arXiv 2019, arXiv:1910.04365. [Google Scholar] [CrossRef]
  194. Katz, S.M.; Maleki, A.; Bıyık, E.; Kochenderfer, M.J. Preference-based Learning of Reward Function Features. arXiv 2021, arXiv:2103.02727. [Google Scholar]
  195. Biyik, E.; Sadigh, D. Batch Active Preference-Based Learning of Reward Functions. In Proceedings of the 2nd Conference on Robot Learning, Zurich, Switzerland, 29–31 October 2018. PMLR 87:519–528. [Google Scholar]
  196. Bıyık, E.; Losey, D.P.; Palan, M.; Landolfi, N.C.; Shevchuk, G.; Sadigh, D. Learning reward functions from diverse sources of human feedback: Optimally integrating demonstrations and preferences. Int. J. Robot. Res. 2022, 41, 45–67. [Google Scholar] [CrossRef]
  197. Sadigh, D.; Dragan, A.; Sastry, S.; Seshia, S. Active Preference-Based Learning of Reward Functions; UC Berkeley: Berkeley, CA, USA, 2017. [Google Scholar] [CrossRef]
  198. Basu, C.; Singhal, M.; Dragan, A.D. Learning from Richer Human Guidance: Augmenting Comparison-Based Learning with Feature Queries. In Proceedings of the 2018 ACM/IEEE International Conference on Human-Robot Interaction, Chicago, IL, USA, 5–8 March 2018; pp. 132–140. [Google Scholar] [CrossRef]
  199. Ran, W.; Chen, H.; Xia, T.; Nishimura, Y.; Guo, C.; Yin, Y. Online Personalized Preference Learning Method Based on In-Formative Query for Lane Centering Control Trajectory. Sensors 2023, 23, 5246. [Google Scholar] [CrossRef] [PubMed]
  200. Kim, C.; Park, J.; Shin, J.; Lee, H.; Abbeel, P.; Lee, K. Preference Transformer: Modeling Human Preferences using Transformers for RL. arXiv 2023, arXiv:2303.00957. [Google Scholar] [CrossRef]
  201. Chen, H.; Yuan, K.; Huang, Y.; Guo, L.; Wang, Y.; Chen, J. Feedback is all you need: From ChatGPT to autonomous driving. Sci. China Inf. Sci. 2023, 66, 166201. [Google Scholar] [CrossRef]
  202. Barendswaard, S.; Pool, D.M.; Boer, E.R.; Abbink, D.A. A Classification Method for Driver Trajectories during Curve-Negotiation. In Proceedings of the 2019 IEEE International Conference on Systems, Man and Cybernetics (SMC), Bari, Italy, 6–9 October 2019; pp. 3729–3734. [Google Scholar] [CrossRef]
  203. Spacek, P. Track Behavior in Curve Areas: Attempt at Typology. J. Transp. Eng. 2005, 131, 669–676. [Google Scholar] [CrossRef]
  204. Ding, J.; Wang, J.; Liu, C.; Lu, M.; Li, K. Driver steering behavior model based on lane-keeping characteristics analysis. In Proceedings of the 17th International IEEE Conference on Intelligent Transportation Systems (ITSC), Qingdao, China, 8–11 October 2014; pp. 623–628. [Google Scholar] [CrossRef]
  205. Wei, C.; Romano, R.; Merat, N.; Wang, Y.; Hu, C.; Taghavifar, H.; Hajiseyedjavadi, F.; Boer, E.R. Risk-based autonomous vehicle motion control with considering human driver’s behaviour. Transp. Res. Part C Emerg. Technol. 2019, 107, 1–14. [Google Scholar] [CrossRef]
  206. Zhou, M.; Qu, X.; Jin, S. On the Impact of Cooperative Autonomous Vehicles in Improving Freeway Merging: A Modified Intelligent Driver Model-Based Approach. IEEE Trans. Intell. Transp. Syst. 2017, 18, 1422–1428. [Google Scholar] [CrossRef]
  207. Teghtsoonian, R.; Teghtsoonian, M. Scaling apparent distance in a natural outdoor setting. Psychon. Sci. 1970, 21, 215–216. [Google Scholar] [CrossRef]
  208. Groeger, J.A. Understanding Driving: Applying Cognitive Psychology to a Complex Everyday Task; Routledge: London, UK, 2000. [Google Scholar] [CrossRef]
  209. Fildes, B.N.; Triggs, T.J. The on effect of changes in curve geometry magnitude estimates of road-like perspective curvature. Percept. Psychophys. 1985, 37, 218–224. [Google Scholar] [CrossRef] [PubMed]
  210. Shinar, D. Curve perception and accidents on curves: An illusive curve phenomenon? Z. Verkehrssicherheit 1977, 23, 16–21. [Google Scholar]
  211. Yang, K.; Liu, Y.; Na, X.; He, X.; Liu, Y.; Wu, J.; Nakano, S.; Ji, X. Preview-scheduled steering assistance control for co-piloting vehicle: A human-like methodology. Veh. Syst. Dyn. 2020, 58, 518–544. [Google Scholar] [CrossRef]
  212. Artuñedo García, A. Decision-Making Strategies for Automated Driving in Urban Environments. Ph.D. Thesis, E.T.S.I. Industriales (UPM), Madrid, Spain, 2019. [Google Scholar]
  213. Wilkie, R.M.; Wann, J.P.; Allison, R.S. Active gaze, visual look-ahead, and locomotor control. J. Exp. Psychol. Hum. Percept. Perform. 2008, 34, 1150–1164. [Google Scholar] [CrossRef] [PubMed]
  214. Robertshaw, K.D.; Wilkie, R.M. Does gaze influence steering around a bend? J. Vis. 2008, 8, 18. [Google Scholar] [CrossRef] [PubMed]
  215. Macuga, K.L.; Beall, A.C.; Smith, R.S.; Loomis, J.M. Visual control of steering in curve driving. J. Vis. 2019, 19, 1. [Google Scholar] [CrossRef] [PubMed]
  216. Kadar, E.E. Mind the Gap: A Theory Is Needed to Bridge the Gap Between the Human Skills and Self-driving Cars. In Robotics and Well-Being; Springer: Cham, Switzerland, 2019; pp. 55–65. [Google Scholar] [CrossRef]
  217. Li, L.; Chen, J. Relative contributions of optic flow, bearing, and splay angle information to lane keeping. J. Vis. 2010, 10, 16. [Google Scholar] [CrossRef] [PubMed]
  218. Mole, C.D.; Kountouriotis, G.; Billington, J.; Wilkie, R.M. Optic flow speed modulates guidance level control: New insights into two-level steering. J. Exp. Psychol. Hum. Percept. Perform. 2016, 42, 1818–1838. [Google Scholar] [CrossRef] [PubMed]
  219. Wann, J.P.; Swapp, D.K. Why you should look where you are going. Nat. Neurosci. 2000, 3, 647–648. [Google Scholar] [CrossRef] [PubMed]
  220. Land, M.F.; Lee, D.N. Where we look when we steer. Nature 1994, 369, 742–744. [Google Scholar] [CrossRef] [PubMed]
  221. Lappi, O. Future path and tangent point models in the visual control of locomotion in curve driving. J. Vis. 2014, 14, 21. [Google Scholar] [CrossRef] [PubMed]
  222. Boer, E. Tangent point oriented curve negotiation. In Proceedings of the Conference on Intelligent Vehicles, Tokyo, Japan, 19–20 September 1996; pp. 7–12. [Google Scholar] [CrossRef]
  223. Lappi, O.; Mole, C. Visuomotor control, eye movements, and steering: A unified approach for incorporating feedback, feedforward, and internal models. Psychol. Bull. 2018, 144, 981–1001. [Google Scholar] [CrossRef] [PubMed]
  224. Sharath, M.N.; Velaga, N.R. Enhanced intelligent driver model for two-dimensional motion planning in mixed traffic. Transp. Res. Part C Emerg. Technol. 2020, 120, 102780. [Google Scholar] [CrossRef]
  225. Zhao, J.; Song, D.; Zhu, B.; Sun, Z.; Han, J.; Sun, Y. A Human-Like Trajectory Planning Method on a Curve Based on the Driver Preview Mechanism. IEEE Trans. Intell. Transp. Syst. 2023, 24, 11682–11698. [Google Scholar] [CrossRef]
  226. Igneczi, G.F.; Horvath, E.; Toth, R.; Nyilas, K. Curve Trajectory Model for Human Preferred Path Planning of Automated Vehicles. Automot. Innov. 2024, 7, 59–70. [Google Scholar] [CrossRef]
Figure 1. The relationships between trajectory planning algorithms, collision risk estimation methods, and user expectation approaches reviewed in this paper.
Figure 1. The relationships between trajectory planning algorithms, collision risk estimation methods, and user expectation approaches reviewed in this paper.
Sensors 24 04808 g001
Figure 2. Spatio-temporal graph-search-based trajectory planning algorithm in [25].
Figure 2. Spatio-temporal graph-search-based trajectory planning algorithm in [25].
Sensors 24 04808 g002
Figure 3. Two-way search tree expansion in Bi-RRT algorithm [46].
Figure 3. Two-way search tree expansion in Bi-RRT algorithm [46].
Sensors 24 04808 g003
Figure 4. The illustration of finite-sampling-based algorithms based on interpolating curves.
Figure 4. The illustration of finite-sampling-based algorithms based on interpolating curves.
Sensors 24 04808 g004
Figure 5. The illustration of shooting optimization trajectory planning algorithms based on optimal control problems.
Figure 5. The illustration of shooting optimization trajectory planning algorithms based on optimal control problems.
Sensors 24 04808 g005
Figure 6. The illustration of collocation optimization trajectory planning algorithms based on control points and parameterized trajectories.
Figure 6. The illustration of collocation optimization trajectory planning algorithms based on control points and parameterized trajectories.
Sensors 24 04808 g006
Figure 7. Intuitive example of transformation from raw sensor data (multi-view images) into mathematical formats suitable for trajectory planning algorithms (3D bounding boxes) [127].
Figure 7. Intuitive example of transformation from raw sensor data (multi-view images) into mathematical formats suitable for trajectory planning algorithms (3D bounding boxes) [127].
Sensors 24 04808 g007
Figure 8. The illustration of typical bounding boxes used in trajectory planning.
Figure 8. The illustration of typical bounding boxes used in trajectory planning.
Sensors 24 04808 g008
Figure 9. The illustration of reachable set considering the obstacle motion predictions and visibility in the field of vision.
Figure 9. The illustration of reachable set considering the obstacle motion predictions and visibility in the field of vision.
Sensors 24 04808 g009
Figure 10. The illustration of driving corridors for convex constraints in the trajectory planning algorithms.
Figure 10. The illustration of driving corridors for convex constraints in the trajectory planning algorithms.
Sensors 24 04808 g010
Figure 11. The illustration of traditional artificial potential field methods for risk estimations.
Figure 11. The illustration of traditional artificial potential field methods for risk estimations.
Sensors 24 04808 g011
Figure 12. The illustration of composite risk field methods for risk estimations.
Figure 12. The illustration of composite risk field methods for risk estimations.
Sensors 24 04808 g012
Table 1. Summary and comparison of graph-search-based planning algorithms.
Table 1. Summary and comparison of graph-search-based planning algorithms.
AlgorithmsProsCons
Exhaustive search [30,31], Dijkstra [22,23,24], UCS [25]Generic, cost function flexibility, optimality in discrete spaceNo heuristic, relatively low calculation efficiency
A* [26,27,28,29]Wide applications, calculation efficiency with heuristic, optimality in discrete spaceRestricted cost definition brought by heuristics
Hybrid A* [32,33], THA* [34]Consideration of kinematic constraints, high efficiency brought by space discretizationSuboptimality in discrete space
ATRWA* [36], D* [37], D* Lite [38], LPA* [39], iADA* [40]Reusing historical planning information, adapting to dynamic environmentsLimited research in autonomous vehicle applications currently
Table 2. Summary and comparison of random-sampling-based planning algorithms.
Table 2. Summary and comparison of random-sampling-based planning algorithms.
AlgorithmsProsCons
PRM [41], PRM* [42]Efficient re-planning in common mapsTime-consuming collision detections
RRT [44]Probabilistically complete, GenericNo asymptotic optimality
RRT-connect [45]Probabilistically complete, high computation efficiencyNo asymptotic optimality
RRT* [42,47,59], Informed RRT* [48]Probabilistically complete, asymptotic optimality, wide applicationsImprovements needed in application details
Kinodynamic RRT* [49], KB-RRT* [50]Advanced dynamic constraints compared with RRT*Low computation efficiency for constraints/Model-driven pruning not reliable enough
FMT* [52], BIT* [53,54,55], EIT* [56]Probabilistically complete, asymptotic optimality, high efficiency based on graph theoryLimited research in autonomous vehicle applications currently
Table 3. Summary and comparison of planning algorithms using interpolating curves.
Table 3. Summary and comparison of planning algorithms using interpolating curves.
AlgorithmsProsCons
Reeds–Shepp [60], Dubins [61]Simple and efficientCurvature discontinuity, low-speed only
Clothoid [63,64]Continuous and linearly changing curvatureNo explicit analytical expressions, low computation efficiency
Third-order spiral [66], S-curve [67]Suitable for applications in special scenarios
Polynomial [68,69], Polynomial spline [70,71,72,73], Bézier spline [74,75]Explicit analytical expressions, high computation efficiency, easy derivatives calculationSuboptimal trajectory potential considering OCP
Table 4. Summary and comparison of shooting numeric optimization planning algorithms.
Table 4. Summary and comparison of shooting numeric optimization planning algorithms.
AlgorithmsProsCons
MPC and its multiple variants [83,84,85,86,88,89,90,91,92,96]Consideration of vehicle dynamics and other constraints, flexible and versatile formulation, inconsistent preview and planning window lengthLow computation efficiency, requirement for problem simplification
iLQR [80,93,94,97,98]Simple problem definitions, high calculation efficiencyOnly linear vehicle dynamics, no explicit hard constraints, consistent preview and planning window length
DDP [81]More accurate vehicle dynamics compared with iLQRLimited research in autonomous vehicle applications currently
Table 5. Summary and comparison of collocation numeric optimization planning algorithms.
Table 5. Summary and comparison of collocation numeric optimization planning algorithms.
AlgorithmsProsCons
NLP optimizations [101,102,103,106]Achieving complex objectives in specific problems while maintaining computational efficiencyTransformations of complex constraints, objectives, and their derivatives required
QP optimizations [71,73,104,105,107,108]Usually high computation efficiency, single optimal solution guaranteedLimited objectives in quadratic forms
Table 6. Summary and comparison of the properties of different trajectory planning algorithm categories.
Table 6. Summary and comparison of the properties of different trajectory planning algorithm categories.
Planning Algorithm CategoryPros Cons Typical Use
Graph searchHigh efficiency in exploring non-convex state spacesFlexible planning objectives, optimal or suboptimal solutions in discrete spacesNon-smoothness in searched trajectories and need post-processingPredefined discretization of the state space and action space requiredServe as “front-end” in trajectory planning frameworks
Random samplingNo predefined space discretization neededRandomness in the planning results
Interpolating curves, finite samplingEasy implementations and low computation burdenHard to cope with complex planning tasks in long time rangesBasic components of other categories
Shooting numeric optimizationContinuous, smooth, and executable trajectory generationDirect and adequate incorporation of vehicle dynamic constraintsTypically rely on initial solutions, convex objectives, state and action constraintsSimplification of optimization problems needed or sacrificing efficiencyServe as “back-end” in trajectory planning frameworks
Collocation numeric optimizationHigher efficiency in realizing multiple planning objectivesIndirect dynamic constraints
End-to-end data-drivenFlexible data utilization and strategy learning methods.Black-box nature, difficulty in locating source of mistakesParadigm and structures in evolution
Table 7. Summary and comparison of risk estimation methods in trajectory planning.
Table 7. Summary and comparison of risk estimation methods in trajectory planning.
MethodProsCons
Surrogate safety measures [128,129,130,131,132,133,134,135,136,137,138,139,140,141,142,143,145,146,147]Simple definitions, clear physical significance, high calculation efficiency, subjective perception consistencyLimited in specific scenarios, discontinuity
RSS [148,149], SFF [150,151], other rule-based safety checkers [152]Generic in complex scenarios, integrated with simulators like CARLANot directly integrated with algorithms, unrealistic rule assumptions
data-driven safety checkers [153,154,156,157]Flexible data fitting ability with good performanceTrained models usually only fit specific driving scenarios
Bounding boxes [74,76,77,79,108,158]Simple definitions, high computation efficiencyLack of detailed information for potential risk estimation
Occupancy grids [160,161]Detailed geometry information for out-of-vocabulary obstaclesPromising but inadequate status information for potential risks currently
Reachable sets [162,163,164,165,166]Capturing abundant scenario informationLack of potential risk information, conservative
Driving corridors [103,126,167]Convex constraints for optimization algorithmsLack of potential risk information
Traditional artificial potential fields [35,89,91,168,169,170,171,172]Unified modeling of multiple risk sources, high calculation efficiency, gradient informationdeviation for realistic risk status or subjective perception
PDRF [144], DRF [173,174]Detailed risk modeling based on probability and severityLow computation efficiency, no gradient information
GDRF [175]More efficient than DRF while detailed, gradient information, subjective perception consistencyRelative lower computation efficiency
Table 8. Summary and comparison of methods utilizing human data in trajectory planning.
Table 8. Summary and comparison of methods utilizing human data in trajectory planning.
MethodProsCons
Imitation learning [18,110,111,112,113,114,115], implicit personalization models [179,180,181,182,183,184], driving style classification [90,186]Data-driven, flexibility in mimicking human driver trajectory dataDeviation from human preferences in some scenarios, clarification of applicability ranges needed
Preference learning [191,192,193,194,195,196,198,199,200]Planning algorithm updates from human feedback directlyLarge amounts of user interactions required currently, algorithm structure under development
Driver behavior modeling [175,204,205,206,224,225,226]Realizing human-like behaviors based on behavioral mechanismIntegration methods of driver models and planning algorithms need further investigation
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

Xia, T.; Chen, H. A Survey of Autonomous Vehicle Behaviors: Trajectory Planning Algorithms, Sensed Collision Risks, and User Expectations. Sensors 2024, 24, 4808. https://doi.org/10.3390/s24154808

AMA Style

Xia T, Chen H. A Survey of Autonomous Vehicle Behaviors: Trajectory Planning Algorithms, Sensed Collision Risks, and User Expectations. Sensors. 2024; 24(15):4808. https://doi.org/10.3390/s24154808

Chicago/Turabian Style

Xia, Taokai, and Hui Chen. 2024. "A Survey of Autonomous Vehicle Behaviors: Trajectory Planning Algorithms, Sensed Collision Risks, and User Expectations" Sensors 24, no. 15: 4808. https://doi.org/10.3390/s24154808

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