Next Article in Journal
A Model for Urban Environment Instance Segmentation with Data Fusion
Previous Article in Journal
Vision-Based Methods for Food and Fluid Intake Monitoring: A Literature Review
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Review

A Review of the Motion Planning and Control Methods for Automated Vehicles

1
School of Electronic Information Engineering, Xi’an Technological University, Xi’an 710021, China
2
School of Marine Science and Technology, Northwestern Polytechnical University, Xi’an 710072, China
*
Author to whom correspondence should be addressed.
Sensors 2023, 23(13), 6140; https://doi.org/10.3390/s23136140
Submission received: 19 May 2023 / Revised: 18 June 2023 / Accepted: 28 June 2023 / Published: 4 July 2023
(This article belongs to the Section Vehicular Sensing)

Abstract

:
The motion planning and control method of automated vehicles, as the key technology of automated vehicles, directly affects the safety, comfort, and other technical indicators of vehicles. The planning module is responsible for generating a vehicle driving path. The control module is responsible for driving the vehicle. In this study, we review the main methods and achievements in motion planning and motion control for automated vehicles. The advantages and disadvantages of various planning and control methods are comparatively analyzed. Finally, some predictions and summaries based on the existing research results and trends are proposed. Through this analysis, it is believed that various types of algorithms will be further integrated in the future to complement each other’s strengths and weaknesses. The next area of research will be to establish more accurate vehicle models to describe vehicle motion, improve the generalization-solving ability of algorithms, and enhance the planning and control of integrated ‘human-vehicle-road’ traffic systems.

1. Introduction

Automated vehicles, also referred to as smart cars or driverless cars, are vehicles that can operate without human intervention using sensors to gather information about their surroundings and generate decision commands to execute driving behaviour. Automated vehicles are highly integrated and complex systems that incorporate modern sensing, information, and communication technologies, automatic control technologies, and artificial intelligence. These high-tech components work together to create an intelligent body for the vehicle. An autonomous driving system is essentially a result of learning, understanding, imitation, and optimization of the three crucial components of the driving process, namely, environment perception, decision planning, and control execution. These components are based on the operational experiences of human drivers [1,2,3,4]. The perception link serves as the foundation of the technology chain, providing real-time data to the intelligent driving system via constant interactions with the surrounding environment. These data include information from onboard sensors, such as vehicle cameras, LIDAR, millimeter wave radar, and positioning systems, as well as real-time road condition data obtained via vehicle–road collaboration and 5G technology. Decision planning aims to utilize environmental sensing to integrate and analyze vehicle–road environment information. This information is then used to obtain the next driving behaviour instruction, which includes both the horizontal and vertical behaviour decision planning of the vehicle. The control execution segment controls the target vehicle based on the results of upper-level planning. To ensure quick and accurate trajectory tracking, the vehicle actuators should have excellent dynamic performance and good system robustness. Currently, automated vehicles operate at level L4, which means that the vehicle operates without human intervention, but only in limited scenarios.
Vehicle motion planning involves generating a geometric path that connects the start and end points of the vehicle, while also providing information on the vehicle’s velocity along the path. This process must also ensure that the vehicle satisfies various constraints, such as kinematic/dynamic constraints and collision avoidance constraints, as well as temporal and/or spatial constraints from the internal system or external environment. However, in practical engineering applications, motion planning is typically divided into a two-stage computational architecture of path planning followed by motion timing. First, the geometric curve of the travel is generated, and then the speed along the planned curve is considered [5].
In the realm of automated vehicles, path planning plays a vital role in the decision-making process. This involves making intelligent decisions to exit the driving task and plan a feasible route based on the information gathered by the vehicle’s sensing devices, including data on surrounding pedestrians, vehicles, and buildings [6]. The path planning module can be broken down into two parts: global planning and local planning. The global path planning module generates a macroscopic path based on the start and end points, but it does not take into account the real-time environment of certain vehicles. The local route planning module of the automated vehicle generates a route with traffic and avoidance functions based on real-time environment information for the control module to follow [7,8,9].
Motion control refers to the process by which an intelligent driving system makes decisions based on the current position, posture, and vehicle speed, among other factors, using a specific logic; the system then sends commands to the throttle, brake, and steering actuators [10,11]. The two main control objectives of motion control are longitudinal control and lateral control, which aim to effectively manage the vehicle’s longitudinal and lateral movements, respectively [12]. Longitudinal control in vehicle control refers to the management of the accelerator and brake to maintain a specific speed, whereas lateral control involves using the steering system to guide the vehicle along a predetermined path [13]. Various control methods have been applied by researchers to construct models for a strongly coupled system of vehicle motion nonlinearity and tire mechanics nonlinearity in lateral control.
This paper provides an overview of the research on the planning and control of automated vehicles. The first section discusses the various vehicle motion planning methods and evaluates their pros and cons. The second section covers the research history and current status of motion control methods for automated vehicles, both domestically and internationally. Additionally, the advantages and disadvantages of the tracking control methods are evaluated. Finally, the paper concludes with an outlook on the future development of planning controls for automated vehicles.

2. Automated Vehicle Motion Planning

2.1. Graph Search Algorithm

The graph search algorithm is used to approximate the motion construction space of a vehicle by dividing it into feasible and infeasible grids based on the regions’ feasibility. The algorithm then searches for paths that meet the driving conditions in two stages: constructing a graph and searching for pathways within it. The visual graph method [14], the Voronoi graph method [15], and the raster decomposition method [16] are the main methods used for graph construction. In graph theory, Dijkstra [17,18] and A* [19,20,21] algorithms are popularly used to explore paths in graphs. Dijkstra is a path search algorithm that is used for finding the shortest path from a single source node. It is often used as a foundational method for solving the shortest path searching problems. On the other hand, the A* algorithm is an exploration method that is based on graph heuristics. It is commonly used to solve search tasks in rasterized maps, as the algorithm’s distance function is incorporated in the definition phase. Figure 1 shows a flowchart of the A* algorithm. However, the accuracy of the planned trajectory depends on the resolution of the map raster. A finer map raster will provide a more accurate trajectory planning, but it will also increase the computational load. Therefore, the graph search algorithm may not be suitable for complex environments. The algorithm generates trajectories that travel close to obstacles, which leads to a high-risk factor during vehicle driving. Moreover, it is less used in autonomous driving systems [22].

2.2. Curve Interpolation Algorithm

To tackle the challenge of computationally intensive graph search methods, scholars have proposed a curve interpolation approach [23,24]. The core idea of this method is to generate paths with high continuity and smoothness, which are subsequently fitted with road point data that satisfy vehicle travel constraints [25]. The selection of the nodes plays a crucial role in this process. Multiple sets of curves are fitted based on these nodes, and the optimal curve is selected based on specific requirements or roadblocks in the problem being addressed.
Polynomial curves have the more commonly used geometric relations in this type of method, which often relies on the selection of the appropriate geometric order to plan paths that meet specific kinematic constraints. For example, Xu et al. [26] presented a motion planner that utilizes polynomials to iteratively optimize the velocity and path for real-time optimization. This process is shown in Figure 2. Glaser et al. [27] used quadratic and quintuple polynomials for lateral and longitudinal planning of vehicles, respectively. Petrov et al. [28] used cubic curves to plan the path of a vehicle overtaking event. Yang et al. [29] used cubic polynomials to plan the path of an automated vehicle changing lanes, and the constraints of the surrounding vehicles were considered when the vehicle changed lanes.
The curve interpolation method is easily traceable. It has a low computational cost and high real-time performance. It is commonly used for smoothing trajectories in combination with other planning methods.

2.3. Sampling-Based Approach

The sampling-based planning methods first need to decide on the solution space, and after dense sampling of the path points in the solution space, a path search from the starting point to the target point is performed through the effective connection between the sampled points. One of the more commonly used methods is the probabilistic roadmap method (PRM) [30], the rapidly exploring random tree (RRT) [31], and the dynamic window approach (DWA) [32,33]. The DWA algorithm is mainly used in robot path planning and low-speed self-driving scenarios [34]. The core of the DWA algorithm lies in sampling and dynamic planning. Sampling mainly includes velocity sampling in the temporal dimension and path sampling in the spatial dimension [35,36]. A schematic diagram of the dynamic window method from the literature [36] is presented in Figure 3.
The RRT algorithm has been utilized in the path planning of automated vehicles to address issues such as path curvature discontinuity and path non-optimality. To improve upon this, Karaman and Frazzoli introduced the RRT* algorithm [37], which guarantees asymptotic optimality and has been further optimized for both calculating feasible solutions and enhancing complexity and stability.
The sampling-based path planning algorithm is a fast and versatile method that considers multiple constraints. However, the accuracy and quantity of sampling greatly affect the quality of the generated paths. In complex traffic scenarios, this may result in path generation failure or require a significant amount of computational resources.

2.4. Artificial Potential Field Method

Khatib proposed the artificial potential field method in 1986, which models the movement of a vehicle in an environment as being influenced by a virtual force field. This method generates repulsive forces between all obstacles in the environment and the vehicle, whereas the goal point generates an attractive force. By searching for directions where the potential field weakens, feasible paths can be planned [38,39,40,41,42]. The overall planning concept is shown in Figure 4. Wahid [43] utilized an artificial potential field method to design a collision avoidance motion planning system. The system was implemented via a combination of a steering control system and a longitudinal distribution system, which enabled the vehicle to track the required motion. In their study, Wang et al. [44] examined the obstacle avoidance behavior of human drivers and used this information to construct an obstacle avoidance safety model. They also improved the artificial potential field method by reconstructing the repulsive field range associated with the obstacles. This resulted in the creation of a collision-free path that is suitable for automated vehicles. The artificial potential field method is a valuable tool for path planning in uncertain and dynamic environments. However, it is important to consider its limitations, such as its tendency to become stuck in the local minima, which can hinder its effectiveness. Additionally, the conventional APF algorithm may prevent the robot from reaching the target point due to obstacles or the influence of repulsive forces. This can make it difficult for the robot to bypass the obstacles and reach the target point.

2.5. Machine Learning Method

In path planning tasks that involve machine learning methods, the model takes in information about the current state of the vehicle and its surrounding environment as input and generates a planned path as output. Several machine learning techniques, such as convolutional neural networks [45,46], long- and short-term memory networks [47], reinforcement learning [48,49], and Hidden Markov decision processes [50] have been utilized for path planning in vehicles. These techniques possess remarkable advantages, including their robust learning capability, ability to predict samples for planning, and fast computational speed. Due to the complexity of traffic environments, it is not possible to achieve complete sample coverage, and there may be limitations.

2.6. Numerical Optimization Algorithm

In the context of self-driving, path planning can be viewed as a multi-objective optimization problem with constraints. As such, numerical optimization methods, such as the model predictive control (MPC) algorithm, are frequently utilized in path planning [51]. Optimal control, another name for numerical optimization, is also a prominent planning algorithm [52]. The MPC obtains the vehicle’s differential equations of motion in the form of a rolling optimization and solves the optimization task by taking into account the environmental and vehicle kinematic constraints [53,54].
Algorithms that are based on numerical optimization techniques enable the integration of multiple objectives in the design process and also take into account the constraints of the vehicle. This results in obtaining higher-quality solutions [55,56]. The vehicle motion planning problem typically involves a non-convex problem with high dimensionality, which can result in local minima and suboptimal solutions. Furthermore, real-time performance is an area that requires improvement in these algorithms. The algorithms that rely on numerical optimization can be utilized for post-processing paths. The outcomes of other planning algorithms can serve as the initial conditions for path optimization.
This section presents an overview of different path-planning methods and compares their effects in Table 1. Each algorithm has its own scope of application, and it is recommended to fuse various algorithms for future applications. However, to achieve more precise vehicle motion planning, it is necessary to combine the vehicle dynamics model, which can significantly increase the computational effort and make it challenging to consider the dynamic constraints. Motion planning in autonomous driving technology is a complex task that presents numerous challenges. These challenges include data processing, robustness, real-time performance, safety assurance, and practical feasibility. To overcome these challenges, it is necessary to consider various factors to comprehensively and continuously optimize and improve the technology. Only then can we achieve a safer, more efficient, and reliable autonomous driving technology.

3. Tracking Control Methods for Automated Vehicles

As one of the main components of an automated vehicle, path tracking is the control of the vehicle to follow a planned path with minimal deviation. The key to designing tracking algorithms is to achieve accurate and stable path tracking. Currently, the main control methods are PID control, robust control, sliding mode control, fuzzy control, pure pursuit control, LQR control, and model predictive control.

3.1. PID Control

PID controllers are widely used in the industry due to their easy implementation and high stability [57]. However, when it comes to self-driving, conventional PID control faces challenges such as difficult parameter optimization and poor control performance. These challenges arise due to the constraints of the vehicle model, instability of the surrounding environment, and non-integrity constraints [58]. Zuo et al. [59] developed a path-tracking control method using a single neuron-adaptive PID to address issues related to frequent control oscillations. They also included a reasonable dead band to ensure accurate front-wheel corner control. The construction of their controller is shown in Figure 5. Similarly, Marino et al. [60] proposed a nested PID control method to tackle the problem of vehicle steering control.
PID control is a commonly used method in engineering, but it has inherent disadvantages in vehicle lateral control due to the coupling of lateral motion and lateral pendulum motion in a multi-state system. Furthermore, the wide range of changes in the vehicle’s longitudinal speed results in significant changes in the system’s time-varying parameters. As a result, it is relatively challenging to ensure the effectiveness of PID control in multi-variable and time-varying systems.

3.2. Robust Control

The robustness of a control system generally refers to the ability of the system to maintain some of its original qualities when its parameters or structure undergo fluctuations. Robustness includes robust stability and robust performance [61]. To enhance the immunity of path-tracking control, robust control uses methods such as frequency shaping [62] and loop shaping [63] to enable the control system to achieve the desired performance under poor operating conditions. Kayacan et al. [64] proposed a novel robust control approach that utilizes path-tracking errors and integrates feedforward and robust control techniques to guarantee precise linear and curvilinear tracking. A linear model predictive controller was developed for this purpose. Jin et al. [65] developed a robust fuzzy controller to address the challenges of nonlinearity in vehicle lateral motion. The controller utilizes the Takagi–Sugeno (T-S) fuzzy modelling approach and its construction is illustrated in Figure 6. Hu et al. [66] proposed a stable and robust yaw moment control method that effectively addressed the challenges posed by side wind disturbances and parameter fluctuations. This method was found to significantly improve the stability of the model. Robust control is often successful in mitigating disturbances, but achieving optimal control can be challenging.

3.3. Sliding Mode Control

Sliding mode control (SMC) is essentially a distinctive type of nonlinear variable structure control, introduced by the Soviet scholar Utkin in the 1950s, and the method’s nonlinearity is manifested in the discontinuity of the control [67]. A unique aspect of this control strategy is that the system’s structure is not static and can be intentionally modified during the dynamic process to adhere to a predetermined ‘sliding mode’ for the system.
According to academic research, the sliding mode design is decoupled from object parameters and perturbations, which results in several benefits such as rapid response, robustness to parameter changes and disturbances, and simple and reliable control action. This information is supported by reference [68]. Jiang et al. [69] modelled the lateral dynamics of the vehicle and designed an SMC that was able to enhance the vehicle’s tracking performance of the desired path, and the whole process of the controller algorithm is shown in Figure 7. Wang et al. [70] presented an SMC method that utilized the convergence law to enable vehicles to accurately and efficiently follow a desired path with smooth movements.
Sliding mode control (SMC) was utilized to handle the uncertainty of the system, resulting in an accelerated convergence speed of the system state and a limited jitter phenomenon. SMC is a reliable method for controlling uncertain systems due to its ability to effectively deal with uncertainties and disturbances. Wang et al. [71] presented an SMC approach that utilized a nonlinear vehicle dynamics model with seven degrees of freedom. The proposed controller was capable of effectively guiding the vehicle to follow the desired yaw rate and path with stability. Simulations and experiments showed that the path-tracking deviation fluctuates less with changes in vehicle speed and road curvature, and the controller has better robustness and adaptability.
The sliding mode control has several advantages, such as its ability to overcome system uncertainty, strong robustness to disturbances and unmodelled dynamics, and a good control effect, particularly for nonlinear systems. However, when the state trajectory reaches the sliding mode surface, it becomes challenging to slide strictly along the surface towards the equilibrium point. Instead, the trajectory may cross back and forth on both sides, causing jitter as it approaches the equilibrium point.

3.4. Fuzzy Control

Fuzzy control is a contemporary approach to automatic control theory that utilizes the principles of fuzzy mathematical theory, which includes fuzzy set theory, fuzzy linguistic variables, fuzzy logic reasoning, etc. Fuzzy control is based on sensor technology, computer technology, and automatic control theory [72,73,74]. The structure of a fuzzy controller typically consists of four key components: fuzzification, knowledge base, fuzzy inference, and clarity. It does not require precise system modelling and is highly fault-tolerant [75,76]. Masmoudi et al. [77] proposed a PI control algorithm that utilized fuzzy logic to achieve the path tracking of omnidirectional robots. By adjusting the PI system parameters to reduce the dynamic changes of the target and the planning errors, the robot can avoid obstacles and reach the end point smoothly. Tang et al. [78] developed a fuzzy control algorithm-based lateral controller for automated vehicles and compared its performance with the MPC lateral controller and the optimized MPC lateral controller that utilized the PSO algorithm. According to the experimental results, the fuzzy control algorithm was found to be appropriate for operating conditions that involve low and medium speeds, and the accuracy under high-speed operating conditions is inferior to that of the MPC algorithm. Diao et al. [79] created a vehicle dynamics model and suggested a dynamic two-point pre-scan strategy. This strategy was used to design a fuzzy controller, which was then used to establish a lateral error model. Using simulation tests, the authors demonstrated that this control strategy was effective for path tracking on roads with large curvatures. Guo et al. [80] proposed a switching controller that utilizes both optimal control and fuzzy control. The optimal control was applied when the vehicle was turning at small angles, whereas the fuzzy control was used when turning at large angles. This approach addressed the issue of mismatching of the controller model caused by the strong nonlinearities that arise in the vehicle during large lateral acceleration conditions. Fuzzy control offers an advantage over traditional control methods as it does not require an exact mathematical model of the controlled object. This is particularly useful in situations where the controlled object is complex or difficult to model mathematically. The use of fuzzy control can be highly effective in situations where a system is subject to uncertainties or disturbances. This makes it a valuable tool in various fields of engineering and science. Specifically, in the case of automated vehicles, which are complex systems with multiple degrees of freedom and coupled mechanical properties of their components, fuzzy controllers can provide effective lateral control.

3.5. Pure Pursuit Control

The pure pursuit control algorithm is a lateral control method that utilizes the monorail model of a vehicle. The tangent point is the centre of the vehicle’s rear axle, and the tangent line is the longitudinal centre line. By controlling the front wheel turning angle of an automated vehicle, it travels along the arc that passes through the pre-scan point. This method is a geometric tracking-based lateral control method [81,82]. It is robust and still tracks curvature discontinuous paths well, but it is difficult to achieve adaptive pre-sighting distances [83,84], as shown in the diagram of pure pursuit control in Figure 8. Amidi was the first to introduce pure tracking algorithms into path-tracking control for mobile robots. The second DARPA challenge was the first to apply path-tracking control to intelligent vehicles in 2005 [85]. The theoretical approach to the control of autonomous vehicles was further enriched by the optimal pre-targetting control theory proposed by Guo et al. [86].
The pre-scan control’s error feedback is mainly determined by the pre-scan point, which is influenced by the curvature of the road and the speed of the vehicle. In situations where the road curvature is large, the path-following control may be a ‘short-cut’, leading to a significant lateral error. Similarly, when the road curvature changes quickly, the error may fluctuate considerably, causing fluctuations in the control output. To address these issues, multi-point pre-scan control methods have been developed as a means of compensating for the limitations of single-point pre-scans. Symonds [87] proposed a new method of pre-scan, which was to perform a multi-point pre-scan to establish a link between the pre-scan error and the actual front wheel turning angle. Rucco et al. [88] employed a multi-point pre-scan control technique. The method used involved selecting multiple pre-scan points and combining the error feedback quantities from these points to minimize fluctuations in the system output. This is a widely used technique for steering control in autonomous vehicles. While pre-scan control has shown promise in certain scenarios, its overall performance is hindered by model limitations and uncertainties surrounding external disturbances and tire side-bias characteristics.

3.6. Linear Quadratic Regulator (LQR) Control

A linear quadratic regulator (LQR) is a type of control system that utilizes state-space equations to create an optimal dynamic controller. The objective function of the controller is a quadratic energy function that takes into account both the system state and the control quantity [89]. The optimal control quantity is determined by minimizing this energy function [90,91]. First, a linear error model is built using the error between the actual vehicle position information and the planned sampling points in each sampling period. Then, by solving the linear quadratic optimization objective function, the optimal solution is obtained to achieve the optimal path-tracking control law acting on the controlled platform of the automated vehicle [92]. Wang et al. [93] introduced an LQR controller that utilizes optimized weighting coefficients. These coefficients were optimized using an improved artificial ant colony algorithm, which results in improved smoothness and operational stability of the vehicle. The whole process of the controller algorithm is shown in Figure 9.
Sun et al. [94] built a control model based on a common bicycle model with the centre of collision as the reference point and proposed a linear quadratic regulator algorithm to design a path-tracking controller to complete tracking of the target path. Wang et al. [95] introduced a combination of a pre-scan strategy and an LQR to regulate the lateral motion parameters of the automated vehicle and explored the effect of the pre-scan distance on the weighting matrix of the controller. Finally, a simulation model was constructed and tested on a real vehicle to verify the controller’s effectiveness. Ni et al. [96] used a four-wheel steering vehicle as the test object to perform lateral motion control. First, the vehicle dynamics equations were constructed, and an error model was established using a pre-sighting strategy. Then, a four-wheel steering vehicle lateral controller implemented in the LQR method was proposed by combining the dynamic model and the error model. Finally, the effectiveness of the algorithm was verified using a simulation model.
According to Ref. [97], the LQR-based lateral controller is prone to overshooting when sudden changes occur in the road curvature. To address this issue, a feedforward control can be incorporated into the road curvature design, resulting in a feed-forward feedback controller that helps to mitigate the overshoot problem and improve the accuracy of lateral control.

3.7. Model Predictive Control

Model predictive control (MPC) is a control strategy that utilizes an optimization method to generate a sequence of control inputs by predicting the system dynamics via a model used for control. This method is also referred to as the rolling time-domain optimal control [98,99]. In MPC, only the current time control quantity is utilized as the control input, and the optimal input value is calculated iteratively by continuously updating the optimization interval using a rolling time-domain approach [100,101,102]. Numerical solutions can be obtained for the finite optimization interval, thereby allowing the model prediction to control systems beyond linear systems, in contrast to optimal control. Nonlinear model predictive control has the disadvantage of requiring a significant amount of computation for the numerical solution of nonlinear systems. This results in a large number of operations that must be completed in the control cycle, which can be a drawback. In the context of lateral control in vehicles, when the control cycle is short, it is necessary to use a linear model for model control due to limitations in computing power. Model predictive control algorithms are a more reliable option and maintain high accuracy even in complex environments, as evidenced by previous studies [103,104,105].
Rafaila et al. [106] presented a nonlinear model predictive control (MPC) approach for the autonomous steering of an automated vehicle. The proposed method utilizes a 2-degree-of-freedom bicycle model and a magic formula tire model. At each time interval t, the vehicle model predicts the future lateral position of the vehicle, denoted as y(t + k|t). The corner control signal, δ(t + k|t), is then determined by solving the extreme value of an objective function. This function aims to minimize the difference between the system output and the desired lateral position, w(t + k|t), while also satisfying a predefined constraint. The variables δ(t) = δ(t|t) and y(t) = y(t|t) in Figure 10 represent the front wheel corner input and vehicle lateral position, respectively.
Wang et al. [107] proposed a variable parameter path-tracking control method for a smart connected vehicle, which was based on the MPC principle, and designed a path-tracking controller for a smart connected vehicle. The method used a vehicle model with a 3-degree-of-freedom model; the system was linearized to determine the quadratic objective function of the system, and the matrix form based on the functional form was determined. Subsequently, offline simulations were conducted on both the Carsim and Simulink platforms to determine the appropriate parameters for the path-tracking controller under various typical working conditions. Ultimately, the system was able to select the optimal control parameters based on the actual road shape and vehicle speed information. The information obtained from the vehicle network can help the intelligently networked vehicle to complete automatic steering. Jiang et al. [108] proposed an adaptive path-tracking control approach for intelligent vehicles using the MPC principle. They designed a path-tracking controller and established a path-tracking comprehensive evaluation index based on the total variance method. The path-tracking effect under different road adhesion coefficients was analyzed by simulation, and the relationship curve between the road adhesion coefficient and the optimal vehicle speed was fitted. According to the different vehicle speeds and road curvatures, the optimal time-domain parameters under all typical curve conditions were obtained using genetic algorithm optimization. The longitudinal vehicle speed and road curvature feedback were introduced into the MPC path-tracking controller, which had adaptive time-domain parameters.
The model predictive control (MPC) algorithm is widely recognized for its superior control performance, but it also has some limitations. One of these limitations is that the algorithm requires multiple optimization solutions to be carried out within the predicted time domain. The complexity of the prediction model can limit its solution efficiency and real-time performance, making it challenging to meet real-time performance requirements. Therefore, it is crucial to optimize the prediction model according to specific requirements to achieve optimal performance in different scenarios.
Table 2 presents a comparison of the results of each control algorithm. It is important to note that other control methods were not included in this study. For example, Yoshimoto [109] proposed an automatic steering algorithm that utilizes image processing. The algorithm is designed to eliminate the sum of the lane split line offset and the lateral deviation. The iterative learning control (ILC) [110] has been proposed as a solution to address the problem of optimal control signal design in automated vehicles, which requires tracking a fixed reference trajectory and addressing repetitive disturbances like inclined roads. This approach has been used in automated vehicle tracking control, as demonstrated by Son [111].
The lateral control of intelligent vehicles has demonstrated effective control efforts via the integration of model predictive control algorithms with other control methods. Various control structures, including series and parallel structures, have been implemented. Additionally, independent control of different controllers under varying operating conditions has been proposed. Currently, there are mainly some typical controllers that can enable the system to respond quickly when dealing with large errors, and other controllers can enable the system to track accurately when dealing with small errors. MPCs, for example, are often combined with other control methods to ensure accuracy and stability. Adaptive control thinking and machine learning are combined. The use of Kalman filtering, convex optimization, nonlinear optimization, and other traditional adaptive and machine learning methods optimizes controller parameters, and it can also improve efficiency and ensure control effects for intelligent vehicles. In increasingly complex environments, these controls can still be fast and stable to complete the tracking of the target path. One of the main challenges in tracking control is accurately modelling the dynamics of the entire vehicle, as well as effectively controlling the coupling of the vehicle in both the lateral and longitudinal directions. Additionally, the controller must account for nonlinearity, uncertainty, and external disturbances within the system.

4. Summary and Outlook

At present, vehicle motion control methods mainly focus on the design of separate horizontal and vertical controllers by decoupling the horizontal and vertical dynamics. Research on cooperative horizontal and vertical control is limited and at the stage of theoretical analysis. Since a control strategy can be used in practical engineering, as well as the characteristics of horizontal and vertical dynamics correlations, the design methods for the coordinated control strategy need to be further studied in depth.
As the use of autonomous vehicles becomes more widespread, it is becoming clear that a single planning and control algorithm may not be sufficient to meet the demands of every scenario. Currently, multiple control algorithms are utilized to achieve the planning and control of a single scene. In the future, various algorithms will likely be integrated in order to complement the strengths of each other. Additionally, as the number of application scenarios increases, it will be important to improve the generalization ability of the algorithms. This will be a key area of research in the future.
Several countries have already begun implementing intelligent transportation systems to improve their overall transportation infrastructure. This involves utilizing vehicle networking technology to provide real-time and accurate information via vehicle sensor systems and vehicle-to-vehicle and vehicle-to-road communication systems. This increased flow of information will allow for more precise path planning for vehicle lateral control, enabling it to participate in the planning and control of the integrated ‘human-vehicle-road’ transportation system.
The multi-vehicle collaboration of automated vehicles still faces great challenges. The interaction of information leads to an exponential increase in the amount of data, and the requirements for arithmetic power are becoming higher and higher. The undulating terrain causes the attitude of the vehicle to change frequently, which requires a high level of spatial and temporal consistency for the collaborative detection of multiple targets. However, the intelligence of the current intelligently networked vehicles is lower than that of human drivers. Therefore, improving the intelligence of intelligently networked vehicles is an important research direction for the future.

Author Contributions

Conceptualization, X.S. and H.G.; methodology, X.S.; formal analysis, X.S.; investigation, H.G., T.D. and Y.G.; resources, X.S. and H.G.; writing—original draft preparation, H.G.; writing—review and editing, X.S.; supervision, T.D., Y.G. and J.L.; funding acquisition, X.S. and K.T. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the Shaanxi Province Key R&D Program Project (Grant No. 2022GY-306) and the Natural Science Foundation of Shaanxi Province (Grant No. 2022JQ-667).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

All data are available within the manuscript.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Chen, H.; Xiong, G.; Gong, J.; Jiang, Y. Introduction to Driverless Cars; Beijing University of Technology Press: Beijing, China, 2014; pp. 15–17. [Google Scholar]
  2. González, D.; Pérez, J.; Milanés, V.; Nashashibi, F. A Review of Motion Planning Techniques for Automated Vehicles. IEEE Trans. Intell. Transp. Syst. 2016, 17, 1135–1145. [Google Scholar] [CrossRef]
  3. Kato, S.; Takeuchi, E.; Ishiguro, Y.; Takeda, K.; Hamada, T. An Open Approach to Autonomous Vehicles. IEEE Micro. 2015, 48, 60–68. [Google Scholar] [CrossRef]
  4. Plessen, M.G. Trajectory planning of automated vehicles in tube-like road segments. In Proceedings of the 2017 IEEE 20th International Conference on Intelligent Transportation Systems (ITSC), Yokohama, Japan, 16–19 October 2017; pp. 1–6. [Google Scholar]
  5. van Hoek, R.; Ploeg, J.; Nijmeijer, H. Cooperative Driving of Automated Vehicles Using B-Splines for Trajectory Planning. IEEE Trans. Intell. Veh. 2021, 6, 594–604. [Google Scholar] [CrossRef]
  6. Katrakazas, C.; Quddus, M.; Chen, W.H.; Deka, L. Real-time motion planning methods for autonomous on-road driving: State-of-the-art and future research directions. Transp. Res. Part C Emerg. Technol. 2015, 60, 416–442. [Google Scholar] [CrossRef]
  7. Liu, X.; Liang, J.; Zhang, H. Dynamic motion planner with trajectory optimisation for automated highway lane-changing driving. IET Intell. Transp. Syst. 2021, 14, 2133–2140. [Google Scholar] [CrossRef]
  8. Ji, J.; Khajepour, A.; Melek, W.W.; Huang, Y. Path planning and tracking for vehicle collision avoidance based on model predictive control with multiconstraints. IEEE Trans. Veh. Technol. 2017, 66, 952–964. [Google Scholar] [CrossRef]
  9. Hu, C.; Gao, H.; Guo, J.; Taghavifar, H.; Qin, Y.; Na, J.; Wei, C. Rise-based integrated motion control of autonomous ground vehicles with asymptotic prescribed performance. IEEE Trans. Syst. Man. Cybern. Syst. 2021, 51, 5336–5348. [Google Scholar] [CrossRef]
  10. Li, B.; Du, H.; Li, W. A potential field approach-based trajectory control for autonomous electric vehicles with in-wheel motors. IEEE Trans. Intell. Transp. Syst. 2016, 18, 2044–2055. [Google Scholar] [CrossRef] [Green Version]
  11. Selby, M.A. Intelligent Vehicle Motion Control. Doctoral Thesis, University of Leeds, Leeds, UK, 2003. [Google Scholar]
  12. Di, H.; Zhang, Y.; Wang, B.; Zhong, G.; Zhou, W. Review on the method and model of intelligent vehicles Lateral control. J. Chongqing Univ. Technol. 2021, 35, 71–81. [Google Scholar]
  13. Li, Y.; Ruan, J.; Li, C.; Fu, M. Longitudinal Motion Control of Intelligent Vehicle. China Mech. Eng. 2006, 42, 94–102. [Google Scholar] [CrossRef]
  14. Oommen, B.; Iyengar, S.; Rao, N.; Kashyap, R. Robot navigation in unknown terrains using learned visibility graphs. Part I: The disjoint convex obstacle case. IEEE J. Robot. Autom. 1987, 3, 672–681. [Google Scholar] [CrossRef]
  15. Canny, J. A Voronoi method for the piano-movers problem. In Proceedings of the 1985 IEEE International Conference on Robotics and Automation, St. Louis, MO, USA, 25–28 March 1985; pp. 530–535. [Google Scholar]
  16. Tian, C.; Liu, Y.; Feng, S.; Zhu, S. Complete Coverage of Known Space-Rectangular Decomposition. J. Eng. Mech. 2004, 40, 56–61. [Google Scholar] [CrossRef]
  17. Cormen, T.H.; Leiserson, C.E.; Rivest, R.L. Introduction to Algorithms; MIT: Cambridge, MA, USA, 2007. [Google Scholar]
  18. Zhu, D.; Sun, J. A New Algorithm Based on Dijkstra for Vehicle Path Planning Considering Intersection Attribute. IEEE Access 2021, 9, 19761–19775. [Google Scholar] [CrossRef]
  19. Liu, H.; Yang, J.; Lu, J.; Tang, Z.; Zhao, C.; Cheng, W. Research on Mobile Robots Motion Planning: A Survey. Strateg. Study CAE 2006, 8, 85–94. [Google Scholar]
  20. Wang, H.; Ma, Y.; Xie, Y. Guo, M. Mobile Robot Optimal Path Planning Based on Smoothing A* Algorithm. J. Tongji Univ. 2010, 38, 1647–1650. [Google Scholar]
  21. Min, H.; Xiong, X.; Wang, P.; Yu, Y. Autonomous driving path planning algorithm based on improved A* algorithm in unstructured environment. P. I. Mech. Eng. D-J. Aut. 2021, 235, 513–526. [Google Scholar] [CrossRef]
  22. Chao, Y.; Sun, W. Dynamic Path Modification for Multi-robot Path Planning. Mech. Sci. Technol. Aerosp. Eng. 2018, 37, 1483–1488. [Google Scholar]
  23. You, C.; Lu, J.; Filev, D.; Tsiotras, P. Autonomous planning and control for intelligent vehicles in traffic. IEEE Trans. Intell. Transp. Syst. 2019, 21, 2339–2349. [Google Scholar] [CrossRef]
  24. Chen, L.; Qin, D.; Xu, X.; Cai, Y.; Ju, X. A path and velocity planning method for lane changing collision avoidance of intelligent vehicle based on cubic 3-D Bezier curve. Adv. Eng. Softw. 2019, 132, 65–73. [Google Scholar] [CrossRef]
  25. Brezak, M.; Petrović, I. Real-time approximation of clothoids with bounded error for path planning applications. IEEE Trans. Robot. 2013, 30, 507–515. [Google Scholar] [CrossRef]
  26. 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]
  27. Glaser, S.; Vanholme, B.; Mammar, S.; Gruyer, D.; Nouvelière, L. Maneuver-based trajectory planning for highly autonomous vehicles on real road with traffic and driver interaction. IEEE Trans. Intell. Transp. Syst. 2010, 11, 589–606. [Google Scholar] [CrossRef]
  28. Petrov, P.; Nashashibi, F. Modeling and nonlinear adaptive control for autonomous vehicle overtaking. IEEE Trans. Intell. Transp. Syst. 2014, 15, 1643–1656. [Google Scholar] [CrossRef] [Green Version]
  29. 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]
  30. Kavraki, L.E.; Svestka, P.; Latombe, J.C.; Overmars, M.H. Probabilistic roadmaps for path planning in high-dimensional configuration spaces. IEEE Trans. Robot. Autom. 1996, 12, 566–580. [Google Scholar] [CrossRef] [Green Version]
  31. LaValle, S.M. Planning Algorithm; Cambridge University Press: Cambridge, UK, 2006; pp. 15–35. [Google Scholar]
  32. Paden, B.; Cap, M.; Yong, S.Z.; Yershov, D.; Frazzoli, E. A Survey of Motion Planning and Control Techniques for Self-driving Urban Vehicles. IEEE Trans. Intell. Veh. 2016, 1, 33–55. [Google Scholar] [CrossRef] [Green Version]
  33. Zhu, Z.; Xie, J.; Wang, Z. Global Dynamic Path Planning Based on Fusion of A* Algorithm and Dynamic Window Approach. In Proceedings of the 2019 Chinese Automation Congress (CAC), Hangzhou, China, 22–24 November 2019; pp. 5572–5576. [Google Scholar]
  34. Werling, M.; Ziegler, J.; Kammel, 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]
  35. Ziegler, J.; Stiller, C. Spatiotemporal state lattices for fast trajectory planning in dynamic on-road driving scenarios. In Proceedings of the 2009 IEEE/RSJ International Conference on Intelligent Robots and Systems, St. Louis, MO, USA, 10–15 October 2009; pp. 1879–1884. [Google Scholar]
  36. Fox, D.; Burgard, W.; Thrun, S. The Dynamic Window Approach to Collision Avoidance. IEEE Robo. Autom. Mag. 2002, 4, 23–33. [Google Scholar] [CrossRef] [Green Version]
  37. 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]
  38. Liu, C.; Zhai, L.; Zhang, X. Research on local real-time obstacle avoidance path planning of unmanned vehicle based on improved artificial potential field method. In Proceedings of the 2022 6th CAA International Conference on Vehicular Control and Intelligence (CVCI), Nanjing, China, 28–30 October 2022; pp. 1–6. [Google Scholar]
  39. Zha, M.; Wang, Z.; Feng, J.; Feng, J.; Cao, X. Unmanned Vehicle Route Planning Based on Improved Artificial Potential Field Method. J. Phy. Conf. Ser. 2020, 1453, 012059. [Google Scholar] [CrossRef] [Green Version]
  40. Pan, Z.; Li, J.; Hu, K.; Zhu, H. Intelligent Vehicle Path Planning Based on Improved Artificial Potential Field Method. Appl. Mech. Mater. 2015, 742, 349–354. [Google Scholar] [CrossRef]
  41. Jurecki, R.S.; Stanczyk, T.L. Modelling Driver’s Behaviour While Avoiding Obstacles. Appl. Sci. 2023, 13, 616. [Google Scholar] [CrossRef]
  42. Cho, J.H.; Pae, D.S.; Lim, M.T.; Kang, T.K. A Real-Time Obstacle Avoidance Method for Autonomous Vehicles Using an Obstacle-Dependent Gaussian Potential Field. J. Adv. Transp. 2018, 2018, 1–15. [Google Scholar] [CrossRef] [Green Version]
  43. 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, VIC, Australia, 13–15 February 2017; pp. 208–213. [Google Scholar]
  44. 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] [Green Version]
  45. Taghavifar, H. Neural Network Autoregressive with Exogenous Input Assisted Multi-Constraint Nonlinear Predictive Control of Autonomous Vehicles. IEEE Trans. Veh. Technol. 2019, 68, 6293–6304. [Google Scholar] [CrossRef]
  46. Chen, Z.; Huang, X. End-to-end learning for lane keeping of self-driving cars. In Proceedings of the 2017 IEEE Intelligent Vehicles Symposium (IV), Los Angeles, CA, USA, 11–14 June 2017; pp. 1856–1860. [Google Scholar]
  47. Nicola, F.; Fujimoto, Y. A LSTM Neural Network applied to Mobile Robots Path Planning. In Proceedings of the 2018 IEEE 16th International Conference on Industrial Informatics (INDIN), Porto, Portugal, 18–20 July 2018; pp. 349–354. [Google Scholar]
  48. Konar, A.; Goswami Chakraborty, S.; Singh, S.J.; Jain, L.C.; Nagar, A.K. A Deterministic Improved Q-Learning for Path Planning of a Mobile Robot. IEEE Trans. Syst. Man Cyber. Syst. 2013, 43, 1141–1153. [Google Scholar] [CrossRef] [Green Version]
  49. Zhu, M.; Wang, X.; Wang, Y. Human-like autonomous car-following model with deep reinforcement learning. Transp. Res. Part C. Emerg. Technol. 2018, 97, 348–368. [Google Scholar] [CrossRef] [Green Version]
  50. Lefevre, S.; Carvalho, A.; Borrelli, F. A Learning-Based Framework for Velocity Control in Autonomous Driving. IEEE Trans. Autom. Sci. Eng. 2016, 13, 32–42. [Google Scholar] [CrossRef]
  51. Hu, X.; Chen, L.; Tang, B.; Cao, D.; He, H. Dynamic path planning for autonomous driving on various roads with avoidance of static and moving obstacles. Mech. Syst. Signal Process 2018, 100, 482–500. [Google Scholar] [CrossRef]
  52. 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 prospects. Annu. Rev. Control 2018, 45, 76–86. [Google Scholar] [CrossRef]
  53. Rosolia, U.; Bruyne, S.D.; Alleyne, A.G. Autonomous Vehicle Control: A Nonconvex Approach for Obstacle Avoidance. IEEE Trans. Control Syst. Technol. 2017, 25, 469–484. [Google Scholar] [CrossRef]
  54. 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]
  55. Li, X.; Sun, Z.; Cao, D.; He, Z.; Zhu, Q. Real-time trajectory planning for autonomous urban driving: Framework, algorithms, and verifications. IEEE ASME Trans. Mechatron. 2015, 21, 740–753. [Google Scholar] [CrossRef]
  56. Funke, J.; Brown, M.; Erlien, S.M.; Gerdes, J.C. Collision avoidance and stabilization for autonomous vehicles in emergency scenarios. IEEE Trans. Control Syst. Technol. 2016, 25, 1204–1216. [Google Scholar] [CrossRef]
  57. Sun, L.; Ma, J.; Yang, B. Fuzzy PID Design of Vehicle Attitude Control Systems. In Proceedings of the 2020 Chinese Control And Decision Conference (CCDC), Hefei, China, 22–24 August 2020; pp. 1826–1830. [Google Scholar]
  58. Cao, J.; Cao, B.; Chen, W.; Xu, P. Neural Network Self-adaptive PID Control for Driving and Regenerative Braking of Electric Vehicle. In Proceedings of the 2007 IEEE International Conference on Automation and Logistics, Jinan, China, 18–21 August 2007; pp. 2029–2034. [Google Scholar]
  59. Zuo, S.; Song, Y.; Wang, L.; Zhou, Z. Neuron-Adaptive PID Based Speed Control of SCSG Wind Turbine System. Abstr. Appl. Analy. 2014, 2014, 1–10. [Google Scholar] [CrossRef] [Green Version]
  60. Marino, R.; Scalzi, S.; Netto, M. Nested PID steering control for lane keeping in autonomous vehicles. Control Eng. Pract. 2011, 19, 1459–1467. [Google Scholar] [CrossRef]
  61. Li, B. Research on Lateral Dynamics Control of Four-Wheel Active Steering Vehicles. Doctoral Thesis, Shanghai Jiao Tong University, Shanghai, China, 2010. [Google Scholar]
  62. Tan, H.S.; Guldner, J.; Patwardhan, S.; Chen, C.; Bouglerl, B. Development of an automated steering vehicle based on roadway magnets—A case study of mechatronic system design. IEEE ASME Trans. Mechatron. 1999, 4, 258–272. [Google Scholar]
  63. Tai, M.; Hingwe, P.; Tomizuka, M. Modeling and control of steering system of heavy vehicles for automated highway systems. IEEE ASME Trans. Mechatron. 2004, 9, 609–618. [Google Scholar] [CrossRef]
  64. Kayacan, E.; Ramon, H.; Saeys, W. Robust trajectory tracking error-based model predictive control for unmanned ground vehicles. IEEE ASME Trans. Mechatron. 2016, 21, 806–814. [Google Scholar] [CrossRef]
  65. Jin, X.; Yu, Z.; Yin, G.; Wang, J. Improving Vehicle Handling Stability Based on Combined AFS and DYC System via Robust Takagi-Sugeno Fuzzy Control. IEEE Trans. Intell. Transp. Syst. 2018, 19, 2696–2707. [Google Scholar] [CrossRef]
  66. Hu, J.; Wang, Y.; Fujimoto, H.; Hori, Y. Robust yaw stability control for in-wheel motor electric vehicles. IEEE ASME. Trans. Mechatron. 2017, 22, 1360–1370. [Google Scholar] [CrossRef]
  67. Feng, Z.; Jiang, H.; Wei, Q.; Hong, Y.; Oluwaleke Ojo, A. Model-free adaptive sliding mode control for intelligent vehicle longitudinal dynamics. Adv. Mech. Eng. 2022, 14, 16878132221110131. [Google Scholar]
  68. Zhao, X.; Liu, H.; Xiong, G.; Gong, J.; Chen, H. Method of Parameter Selection for Automatic Steering Sliding Mode Control. Trans. Beijing Inst. Technol. 2011, 31, 1174–1178. [Google Scholar]
  69. Jiang, L.; Wu, Z. Sliding Mode Control for Intelligent Vehicle Trajectory Tracking Based on Reaching Law. Trans. Chin. Soc. Agric. Mach. 2018, 49, 381–386. [Google Scholar]
  70. Wang, J.; Steiber, J.; Surampudi, B. Autonomous ground vehicle control system for high-speed and safe operation. Int. J. Veh. Auton. Syst. 2009, 7, 18–35. [Google Scholar] [CrossRef]
  71. Wang, J.; Chen, W.; Wang, T.; Wang, M.; Xiao, L. Vision Guided Intelligent Vehicle Lateral Control Based on Desired Yaw Rate. J. Mech. Eng. 2012, 48, 108–115. [Google Scholar] [CrossRef]
  72. Shi, W.; Sun, T.; Ma, Y.; Chen, Y. Adaptive fuzzy path following control for a nonholonomic mobile robots. In Proceedings of the 10th World Congress on Intelligent Control and Automation, Beijing, China, 6–8 July 2012; pp. 204–208. [Google Scholar]
  73. He, F.; Huang, Q. Time-Optimal Trajectory Planning of 6-DOF Manipulator Based on Fuzzy Control. Actuators 2022, 11, 332. [Google Scholar] [CrossRef]
  74. Fang, Y.; Wang, S.; Bi, Q.; Wu, G.; Guan, W.; Wang, Y.; Yan, C. Research on Path Planning and Trajectory Tracking of an Unmanned Electric Shovel Based on Improved APF and Preview Deviation Fuzzy Control. Machines 2022, 10, 707. [Google Scholar] [CrossRef]
  75. Silva, M.; Garrote, L.; Moita, F.; Martins, M.; Nunes, U. Autonomous electric vehicle: Steering and path-following control systems. In Proceedings of the 16th IEEE Mediterranean Electrotechnical Conference, Yasmine Hammamet, Tunisia, 25–28 March 2012; pp. 442–445. [Google Scholar]
  76. Xiong, L.; Yang, X.; Zhuo, G.; Leng, B.; Zhang, R. Review on Motion Control of Autonomous Vehicles. J. Mech. Eng. 2020, 56, 127–143. [Google Scholar]
  77. Masmoudi, M.S.; Krichen, N.; Masmoudi, M.; Derbel, N. Fuzzy logic controllers design for omnidirectional mobile robot navigation. Appl. Soft Comput. 2016, 49, 901–919. [Google Scholar] [CrossRef]
  78. Tang, C.; Zhao, Y.; Zhao, Y.; Zhou, S. Research on the Trajectory Tracking Control Method of Intelligent Vehicles. J. Northeast Univ. 2020, 41, 1297–1303. [Google Scholar]
  79. Diao, Q.; Zhang, Y.; Zhu, L. A Lateral and Longitudinal Fuzzy Control of Intelligent Vehicles with Double Preview Points for Large Curvature Roads. China Mech. Eng. 2019, 30, 1445–1452. [Google Scholar]
  80. Guo, J.; Hu, P.; Li, L.; Wang, R.; Guo, L. Mixed Lateral Controller Design for Intelligent Vehicle Based on Switching. Trans. Chin. Soc. Agric. Mach. 2012, 43, 1–5. [Google Scholar]
  81. Liu, Y.; Shi, G.; Chen, Y.; Shi, L. Fuzzy Path Following Control Method Based on Pure Pursuit Model. Mach. Des. Res. 2022, 38, 136–140+157. [Google Scholar]
  82. Huang, Y.; Luo, W.; Lan, H. Adaptive Pre-Aim Control of Driverless Vehicle Path Tracking Based on a SSA-BP Neural Network. World Electr. Veh. J. 2022, 13, 55. [Google Scholar] [CrossRef]
  83. Ming, T. Research on Trajectory Tracking Control for Intelligent Vehicles. Master Thesis, Jilin University, Jilin, China, 2016. [Google Scholar]
  84. Wang, H.; Chen, X.; Chen, Y.; Li, B.; Miao, Z. Trajectory Tracking and Speed Control of Cleaning Vehicle Based on Improved Pure Pursuit Algorithm. In Proceedings of the 2019 Chinese Control Conference (CCC), Guangzhou, China, 27–30 July 2019; pp. 4348–4353. [Google Scholar]
  85. Urmson, C.; Ragusa, C.; Ray, D.; Anhalt, J.; Bartz, D.; Galatail, T.; Gutierrez, A.; Joshnston, J.; Harbaugh, S.; Messner, W.; et al. A robust approach to high-speed navigation for unrehearsed desert terrain. J. Field Robot. 2006, 23, 467–508. [Google Scholar] [CrossRef] [Green Version]
  86. Guo, K.; Guan, H. Modelling of Driver/Vehicle Directional Control System. Veh. Syst. Dyn. 1993, 22, 141–184. [Google Scholar] [CrossRef]
  87. Symonds, P.; Sharp, R.S.; Casanova, D. A Mathematical Model for Driver Steering Control, with Design, Tuning and Performance Results. Veh. Syst. Dyn. 2000, 33, 289–326. [Google Scholar] [CrossRef]
  88. Rucco, A.; Notarstefano, G.; Hauser, J. An Efficient Minimum-Time Trajectory Generation Strategy for Two-Track Car Vehicles. IEEE Trans. Control Syst. Technol. 2015, 23, 1505–1519. [Google Scholar] [CrossRef]
  89. Gong, D.; Pan, Q.; Zuo, G.; Li, X. LQR control for a self-balancing unicycle robot on Inclined Plane. J. Syst. Des. Dyn. 2012, 6, 685–699. [Google Scholar]
  90. Zhong, J. A Comparative Study of LQR and MPC Controllers in the Application of Parking Path Tracking. Auto Time 2020, 39, 21–22. [Google Scholar]
  91. Wu, L.; Zhou, R.; Bao, J.; Yang, G.; Sun, F. Vehicle Stability Analysis under Extreme Operating Conditions Based on LQR Control. Sensors 2022, 22, 9791. [Google Scholar] [CrossRef]
  92. Yan, Y.; LI, M. Path tracking of agricultural vehicles based on single neuron adaptive PID control. Mach. Des. Manuf. 2020, 356, 228–231+235. [Google Scholar]
  93. Wang, Y.; Luo, J.; Luo, X.; Yang, X.; Yu, F. Design of LQR controllers of active suspensions based on improved artificial bee colony algorithm. Noise Vib. Control 2021, 41, 61–66. [Google Scholar]
  94. Sun, H.; Li, Y.; Zhao, L.; Wang, Y.; Wang, Y.; Zhao, J. Research on vehicle trajectory tracking control based on optimal slip ratio. Automob. Appl. Technol. 2020, 312, 61–64. [Google Scholar]
  95. Wang, R.; Zhang, R.; Chu, J.; You, F. Optimizing design and quality analysis for CyberCar controller. Trans. Chin. Soc. Agric. Mach. 2007, 38, 22–25. [Google Scholar]
  96. Ni, L.; Lin, F.; Wang, K. Research on path-following control of intelligent vehicles based on preview model. J. Chongqing Univ. Technol. 2017, 31, 27–33. [Google Scholar]
  97. Althoff, M.; Dolan, J.M. Online Verification of Automated Road Vehicles Using Reachability Analysis. IEEE Trans. Robot. 2017, 30, 903–918. [Google Scholar] [CrossRef] [Green Version]
  98. Coppola, A.; Lui, D.G.; Petrillo, A.; Santini, S. Eco-Driving Control Architecture for Platoons of Uncertain Heterogeneous Nonlinear Connected Autonomous Electric Vehicles. IEEE Trans. Intell. Transp. Syst. 2022, 23, 24220–24234. [Google Scholar] [CrossRef]
  99. Batkovic, I.; Zanon, M.; Falcone, P. AI-Enabled Technologies for Autonomous and Connected Vehicles; Springer International Publishing: Cham, Switzerland, 2022; pp. 255–282. [Google Scholar]
  100. Luo, Y.; Chen, T.; LI, K. Nonlinear model predictive cruise control of hybrid electric vehicle. J. Mech. Eng. 2015, 51, 11–18. [Google Scholar] [CrossRef]
  101. Zhang, L.; Wu, G.; Guo, X. Path Tracking Using linear time-varying model predictive control for autonomous vehicle. J. Tongji Univ. 2016, 44, 1595–1603. [Google Scholar]
  102. Hu, J.; Hu, Y.; Chen, H.; Liu, K. Research on trajectory tracking of unmanned tracked vehicles based on model predictive control. Acta Armamentarii. 2019, 40, 456–463. [Google Scholar]
  103. Li, S.; Wang, J.; Li, K. Stability method for predictive control system of soft constrained linear model. J. Tsinghua Univ. Sci. Technol. 2010, 50, 1148–1152. [Google Scholar]
  104. Xiong, G.; Lu, H.; Guo, K.; Chen, H. Research on trajectory prediction of tracked vehicles based on real time slip estimation. Acta Armamentarii. 2017, 38, 600–607. [Google Scholar]
  105. Li, S.; Jia, Z.; Li, K.; Cheng, B. Fast online computation of a model predictive controller and its application to fuel economy: Oriented adaptive cruise control. IEEE Trans. Intell. Transp. Syst. 2015, 16, 1199–1209. [Google Scholar] [CrossRef]
  106. Rafaila, R.C.; Livint, G. Nonlinear model predictive control of autonomous vehicle steering. In Proceedings of the 19th International Conference on System Theory, Control and Computing (ICSTCC), Cheile Gradistei, Romania, 14–16 October 2015; pp. 466–471. [Google Scholar]
  107. Wang, Y.; Cai, Y.; Chen, L.; Wang, H.; He, Y. Design of Intelligent and Connected Vehicle Path Tracking Controller Based on Model Predictive Control. J. Mech. Eng. 2019, 55, 136–144. [Google Scholar] [CrossRef] [Green Version]
  108. Jiang, H.; Wei, Q.; Li, A.; Tang, B.; Geng, G. An operating condition adaptive path tracking control method for intelligent vehicle. J. Chongqing Univ. Technol. 2022, 36, 1–11. [Google Scholar]
  109. Yoshimoto, K.I.; Ogawa, H.; Kubota, H. Course tracking control algorithm using visual information. Veh. Syst. Dyn. 1997, 28, 385–398. [Google Scholar] [CrossRef]
  110. Van Nguyen, L.; Huy Dao, D. Iterative Learning Control For Autonomous Driving Vehicles. In Proceedings of the International Conference on Advanced Technologies for Communications (ATC), Hanoi, Vietnam, 17–19 October 2019; pp. 243–247. [Google Scholar]
  111. Son, T.D.; Nguyen, L.; Van Der Auweraer, H. Learning Control Applications for Autonomous Driving in Extreme Maneuver Scenarios. In Proceedings of the 21st International Conference on Control, Automation and Systems (ICCAS), Jeju, Republic of Korea, 12–15 October 2021; pp. 974–979. [Google Scholar]
Figure 1. A flowchart of the A* algorithm.
Figure 1. A flowchart of the A* algorithm.
Sensors 23 06140 g001
Figure 2. Two-part trajectory planning framework.
Figure 2. Two-part trajectory planning framework.
Sensors 23 06140 g002
Figure 3. Dynamic window.
Figure 3. Dynamic window.
Sensors 23 06140 g003
Figure 4. The concept of the artificial potential field method.
Figure 4. The concept of the artificial potential field method.
Sensors 23 06140 g004
Figure 5. The block diagram of the single neuron-adaptive PID controller.
Figure 5. The block diagram of the single neuron-adaptive PID controller.
Sensors 23 06140 g005
Figure 6. The vehicle control system architecture.
Figure 6. The vehicle control system architecture.
Sensors 23 06140 g006
Figure 7. The algorithm process.
Figure 7. The algorithm process.
Sensors 23 06140 g007
Figure 8. The diagram of pure pursuit control.
Figure 8. The diagram of pure pursuit control.
Sensors 23 06140 g008
Figure 9. The structure of the controller.
Figure 9. The structure of the controller.
Sensors 23 06140 g009
Figure 10. The model predictive control.
Figure 10. The model predictive control.
Sensors 23 06140 g010
Table 1. The planning algorithm comparisons.
Table 1. The planning algorithm comparisons.
AlgorithmsComments
Graph search algorithmThe amount of computation increases dramatically with increasing accuracy and is not suitable for application in complex environments.
Curve interpolation algorithmLow computational cost and high real-time performance.
Sampling-based approachThe solution speed is fast, but the solution accuracy is not high.
Artificial potential field methodA relatively large advantage is path planning in uncertain dynamic environments, but it is easy to fall into local minima.
Machine learning methodsFast computational speed and good generalization capability, but a large number of training samples are required.
Numerical optimization algorithmsMore efficient solving, but real-time performance needs to be improved.
Table 2. Control algorithm comparison.
Table 2. Control algorithm comparison.
AlgorithmsComments
PID controlIt has the advantages of easy implementation and high stability, but the parameters are difficult to optimize and the control performance is poor.
Robust controlIt is highly resistant to interference, but it is difficult to achieve the optimal state.
Sliding mode controlIt has a fast response, is insensitive to parameter changes and disturbances, and has simple and reliable control action.
Fuzzy controlIt does not require precise system modelling and is fault-tolerant, but relies excessively on rule bases.
Pure pursuit controlIt has better robustness but is sensitive to speed changes and prone to overshoot.
Linear quadratic regulator (LQR) controlIt utilizes lower cost to obtain better control performance with high practicality, and it has better robustness against the effect of noise.
Model predictive controlIt is easy to model, has better system robustness and stability, and can effectively deal with multivariate, constrained problems.
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

Song, X.; Gao, H.; Ding, T.; Gu, Y.; Liu, J.; Tian, K. A Review of the Motion Planning and Control Methods for Automated Vehicles. Sensors 2023, 23, 6140. https://doi.org/10.3390/s23136140

AMA Style

Song X, Gao H, Ding T, Gu Y, Liu J, Tian K. A Review of the Motion Planning and Control Methods for Automated Vehicles. Sensors. 2023; 23(13):6140. https://doi.org/10.3390/s23136140

Chicago/Turabian Style

Song, Xiaohua, Huihui Gao, Tian Ding, Yunfeng Gu, Jing Liu, and Kun Tian. 2023. "A Review of the Motion Planning and Control Methods for Automated Vehicles" Sensors 23, no. 13: 6140. https://doi.org/10.3390/s23136140

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