Articles | Volume 12, issue 1
https://doi.org/10.5194/ms-12-419-2021
https://doi.org/10.5194/ms-12-419-2021
Review article
 | 
16 Apr 2021
Review article |  | 16 Apr 2021

Review article: State-of-the-art trajectory tracking of autonomous vehicles

Lei Li, Jun Li, and Shiyi Zhang
Abstract

Air pollution, energy consumption, and human safety issues have aroused people's concern around the world. This phenomenon could be significantly alleviated with the development of automatic driving techniques, artificial intelligence, and computer science. Autonomous vehicles can be generally modularized as environment perception, path planning, and trajectory tracking. Trajectory tracking is a fundamental part of autonomous vehicles which controls the autonomous vehicles effectively and stably to track the reference trajectory that is predetermined by the path planning module. In this paper, a review of the state-of-the-art trajectory tracking of autonomous vehicles is presented. Both the trajectory tracking methods and the most commonly used trajectory tracking controllers of autonomous vehicles, besides state-of-art research studies of these controllers, are described.

Dates
1 Introduction

An autonomous vehicle is a motor vehicle that uses artificial intelligence, sensors, and global positioning system coordinates to drive itself without the active intervention of a human operator (Anagnostopoulos, 2012). Autonomous cars can communicate with each other to reduce traffic congestion and offer greater ease of travel for the elderly and disabled (Zhang and Braun, 2017; Wu et al., 2015).

Autonomous driving techniques have undergone rapid development in the last few decades. Lots of researchers have devoted themselves to reach the ultimate goal – fully automatic driving. Relevant automatic driving techniques like adaptive cruise control (ACC), lane keeping assistance, and lane departure warning (Kuutti et al., 2021) are largely utilized in commercial cars as a consequence of automakers' competition in autonomous vehicle production. Currently, autonomous vehicles can be divided into 0–5 levels by SAE International according to the degree of autonomy (SAE On-Road Automated Vehicle Standards Committee, 2014). Most commercial vehicles can only achieve level 1 to level 2 autonomy due to the available sensor constraints and high costs. They also require sustained attention and control. Tesla Model S and Model X can achieve level 3 autonomy (Van Brummelen et al., 2018). Level 4 is achieved by the Renault SYMBIOZ autonomous vehicle (Drezet et al., 2019). However, mass production is not possible yet due to the high sensor price. According to the latest survey, by 2040, the proportion of people traveling by autonomous taxi and public transport in Germany will have increased from 20.0 % to about 32 % (Kaltenhäuser et al., 2020), which means autonomous vehicles will play an essential role in public transport. This is also in line with the concept of energy saving and global green environmental protection. For an overall understanding of control flow, the general construction of autonomous vehicles is illustrated in Fig. 1. In the figure, x, y, r, vx, and vy are the x axis, y axis, yaw rate, longitudinal velocity, and lateral velocity respectively. All of them can be achieved through the environment perception module. e, θ, and δ represent the tracking error, orientation angle, and steering angle respectively. Autonomous vehicles can be modularized as environment perception, path planning, and trajectory tracking. Essential pieces of information about the vehicle will be detected with sensors in the environment perception module. Then, the path planning module will utilize that information to generate a reference trajectory. Finally, control variables are sent to the vehicle through the trajectory tracking module.

https://ms.copernicus.org/articles/12/419/2021/ms-12-419-2021-f01

Figure 1General structure of autonomous vehicles.

Download

The trajectory tracking block aims to ensure the vehicle can follow a predetermined trajectory generated offline by the navigation system or online by the trajectory planning module (Raffo et al., 2009; Kayacan et al., 2015). The performance of trajectory tracking directly determines the driving performance of autonomous vehicles. This paper presents a review of the current development of the trajectory tracking of autonomous vehicles. The relative techniques of motion control have been used since the 1950s. Some classic control methods and relatively new methods have been established in the last few decades. In this paper, some comparisons between the most commonly used control methods are presented; state-of-art research studies of these control methods are also described.

The structure of this paper is formed as the following sections: Sect. 2 presents the basic control principle of the two most used tracking methods. Section 3 illustrates the state-of-the-art research studies of the widely used controllers.

2 Trajectory tracking methods

Generally, control methods for the trajectory tracking of autonomous vehicles can be decoupled into two types: geometric methods and model-based methods. Vehicle modeling is needed before the tracking controllers are designed. Both of the methods can use the preview strategy or not (Zhang and Zhu, 2019). This section describes the basic modeling of each method according to the reference trajectory. Besides, some optimizations improving vehicle modeling are present.

2.1 Geometric methods

Geometric-based tracking controllers are widely applied in autonomous vehicles. The geometric properties of vehicle and path are considered in the design of controllers, for example, position. The geometric methods have a simple structure and are easy to obtain compared with the model-based methods since the geometric properties are easier to obtain than the kinematic/dynamic properties. Therefore, geometric methods are only suitable for vehicles whose dynamic characteristics are ignored. What's more, it is challenging to achieve a trade-off between tracking performance and stability (Dixit et al., 2018). This section illustrates the two most used geometric-based control methods for autonomous vehicles: the Stanley method and the pure pursuit (PP) method.

2.1.1 Pure pursuit method

The pure pursuit (PP) method has been widely utilized in dealing with path tracking problems of vehicles or robots due to its simplicity and good performance. The tracking performance of the PP method is strongly affected by the selection of a look-ahead point in a practical scenario (Li et al., 2019; Cibooglu et al., 2017).

The PP method utilizes geometric information to calculate the desired control input (steering angle), which can be seen in Fig. 2. In the figure, δ, L, and ld stand for steering angle, wheelbase, and look-ahead distance respectively. α is the angle between the look-ahead vector and the heading angle. The dashed line represents the reference trajectory (all the reference trajectories in this paper are represented with dashed lines, for the discrete point is used in the practical scenario), and the vehicle model has been expressed by a 2 degree of freedom (2 DOF) bicycle model. As can be seen in this figure, the PP method geometrically calculates the steering angle based on the α. The outcome results of the steering angle will apply to control vehicles directly. In the Ackerman 2 DOF model, the steering angle δ can be expressed as follows (Li et al., 2018):

(1) δ = tan - 1 2 L sin ( α ) l d .

As can be seen in Eq. (1), only look-ahead distance (ld) is available to be adjusted. It is similar to proportional gain control in that the lateral offset is proportional to the look-ahead distance (Rajamani, 2011; Domina and Tihanyi, 2019b). The excellent tracking performance is related to a suitable look-ahead distance in this method. The longer this distance, the smoother the response, but large corner cuttings may be followed to decrease the tracking performance. The corner cutting phenomenon can be alleviated by using a proportional term of a PID (proportional–integral–derivative) controller (Park et al., 2015). In addition, the shorter this distance, the more precise the tracking performance will be. However, the oscillations happened because of the rapid changes of control signals which cause the vehicle to be unstable and the comfort of passengers to be decreased (Domina and Tihanyi, 2019b). Chen et al. (2018) put forward a low-pass filter to reduce the oscillations. Cibooglu et al. (2017) combined the PP method and Stanley method to accommodate this phenomenon. Consequently, choosing the appropriate look-ahead distance has become a significant part of the PP controller design. An optimization choice of look-ahead distance with learning-based algorithms like the Gaussian mixture model (GMM) and the velocity-based Gaussian mixture regression (GMR) (Li et al., 2018) is possible. A traditional feedback PID controller is designed to automatically tune the look-ahead distance in Chen et al. (2018), but the effect of speed is ignored. And the fuzzy controller is another strategy to calculate the look-ahead distance (Wang et al., 2019a). Li et al. (2019) utilized a formula with velocity and curvature of the path to calculate the desired look-ahead distance, for velocity is related to the look-ahead distance (Wang et al., 2019a). All strategies mentioned above focus on look-ahead point choosing, while Zou et al. (2018) replace the look-ahead point with a preview point that is closely related to the turning radius. They calculate the steering angle by utilizing a double circular arc tracking model that consists of two arcs of little different curvature between the preview point and the vehicle. This could make the points change continuously and slightly when vehicles need to make a lane change or need to turn. The PP method is difficult to apply to high-speed autonomous vehicles (beyond 18 km/h) because of the characteristics of the look-ahead distance. Therefore, the receding horizon control approach is presented by Elbanhawi et al. (2018) to help autonomous vehicles to drive stably at speeds of up to 100 km/h.

https://ms.copernicus.org/articles/12/419/2021/ms-12-419-2021-f02

Figure 2The pure pursuit method.

Download

2.1.2 Stanley method

The Stanley method is another popular geometric method of trajectory tracking, which was first applied in the Stanley autonomous vehicle by Stanford University in the 2005 DARPA Grand Challenge, gaining first prize (Buehler et al., 2007). The control law of the Stanley method is to address the cross-track error between the closest point of the path and the front wheel and orientation error to converge toward zero (Cibooglu et al., 2017), as can be seen in Fig. 3. In the figure, θe is the orientation error between the heading of the ego vehicle and the direction of the closest point P. k is the track error gain, e is the cross-track error, v is the longitudinal velocity, and δ is the steering angle. The dashed curved line represents the reference trajectory, and the 2 DOF bicycle model is utilized. The control input representing the steering angle can be calculated (Zhu et al., 2016) as

(2) δ = θ + tan - 1 k e v x .

The difference between the Stanley method and the PP method is the tracking error of the Stanley method, which is calculated with the front wheel. In contrast, the PP method is calculated with the rear wheel, and the look-ahead distance is neglected in the Stanley method (Amer et al., 2018). Thus, the Stanley method can converge to the reference path with a quick speed (Martin et al., 2013). The parameter k should be determined beforehand concerning current vehicle states, and it is proportional to convergent speed. Thus, an adaptive tuning approach of k is designed by using neural dynamic programming (NDP) according to information on the vehicle state and reference trajectory in Zhu et al. (2016).

https://ms.copernicus.org/articles/12/419/2021/ms-12-419-2021-f03

Figure 3The Stanley method.

Download

The Stanley method has a good trajectory tracking performance on smooth paths and a poor performance on paths that have a rapid change of curvature. Therefore, modeling a continuous curvature path rather than a discrete point can improve tracking performance (Andersen et al., 2016). Furthermore, the vehicle using the Stanley method will not turn a corner until the error appears, for the look-ahead point is missing (Domina and Tihanyi, 2019a). Yang et al. (2017) utilized the logarithmic relationship between the vehicle speed and the fixation point to calculate the position of the desired preview point. After that, the Stanley controller can track the position instead of the closest point of the path to improve the curvature calculate efficiency of the Stanley method. The strategy of the preview point is also presented in Zhang and Zhu (2019).

The Stanley method maintains good precision of tracking at low speed but having an opposite effect at high speed (Dominguez et al., 2016). This could be eased by designing a gain parameter to automatically allocate weighting of the combined PP method and Stanley method, for their features are opposite (Cibooglu et al., 2017; Domina and Tihanyi, 2019a). Considering the relative parameters of the Stanley method need to be iteratively tuned in real driving scenarios, the adaptive parameters' tune controller can make this process easier (Amer et al., 2018).

2.2 Model-based tracking methods

Model-based tracking methods are more suitable for autonomous vehicles in real driving scenarios. Nevertheless, the complexity and computation of this method are increased due to kinematic/dynamic properties compared with geometric methods. The model-based tracking method can be divided into kinematic-model-based methods and dynamic-model-based methods. This subsection will describe the basic model and some improvements for these two methods.

2.2.1 Kinematic-model-based methods

The kinematic model takes the position, velocity, acceleration, and yaw rate, etc. of the vehicle into consideration rather than the relationship between the actual position of the vehicle and its dimensions, which are commonly applied in geometric methods (Bacha et al., 2017). The kinematic-model-based controllers use the velocity and steering angle as the control variables to control the vehicles, and the geometric relationship between the kinematic model and the reference path for the bicycle model is presented in Fig. 4.

https://ms.copernicus.org/articles/12/419/2021/ms-12-419-2021-f04

Figure 4Kinematic model with path.

Download

The state space of this control system is calculated by

(3) w ˙ d ˙ θ ˙ e δ ˙ = cos ( θ ) 1 - d k ( w ) sin ( θ e ) tan ( δ ) L - k w cos ( θ e ) 1 - d k ( w ) 0 v + 0 0 0 1 δ ˙ ,

where θ is the orientation angle of the vehicle in the global frame, d is the vertical distance from the center of the rear axis to the path, θe is the orientation error (θe=θ-θd), w is a function of the path, k(w) is the curvature of the path, L is the wheelbase, δ is the steering angle, and v is the longitudinal velocity. More details can be found in Snider (2006).

The bicycle model is a simplified model of a vehicle of which the two front wheels and two rear wheels are regarded as one due to the symmetric structure. The roll and pitch dynamics are neglected, and the small-angle assumption is applied for the angle of steering, sideslip, and yaw (Tagne et al., 2013). The neglection of roll dynamics is unsuitable for the vehicle with a high center of gravity, which lacks active devices on the suspension (Ley-Rosas et al., 2019). To get a realistic roll dynamic response, Kanchwala (2019) used an additional 2 DOF model for the angular velocity of rear wheels, which can describe the roll dynamics of the vehicle. Ley-Rosas et al. (2019) proposed a nonlinear reduced-order observer based on the higher order sliding model to estimate the lateral velocity, roll angle, and roll rate. The small-angle assumption was verified to produce a lower tracking performance compared with the complete angle by Guo et al. (2019); they applied the full-angle method in that article.

It can be inferred from Eq. (3) that this kinematic model has a low dependence on parameters, which means this method is widely used (Alcala et al., 2018b). However, for the same reason, the kinematic-based controller may not be able to work in scenarios like steep slopes or slippery ground due to tire forces changing prominently when tire sliding will appear. To solve this problem, Fang et al. (2011) proposed a controller based on the kinematic model with the tire model. In consideration of the fact that dynamic features of vehicles are neglected in kinematic models, kinematic controllers are not suitable for high-speed vehicles (Dixit et al., 2018). A compensator is designed by Tang et al. (2020) to correct the error of kinematic model prediction of the model predictive controller (MPC) whose output is the yaw rate rather than steering angle to expand the velocity range from low speed to high speed. To have a smooth driving capability, a crabbing angle was introduced in the extended kinematic model (Pereira et al., 2017).

2.2.2 Dynamic-model-based methods

The dynamic model is an extended model of the kinematic model and geometric model. All features of the kinematic model and geometric model were illustrated before they are utilized in the dynamic model. As illustrated in Fig. 5, the dynamic model describes the motion of the vehicles which includes the position, velocity, and acceleration of the vehicle. The motions are computed through internal forces, energy, or momentum of the system (Amer et al., 2017).

https://ms.copernicus.org/articles/12/419/2021/ms-12-419-2021-f05

Figure 5Lateral dynamic model of the bicycle model.

Download

The equation of the lateral dynamic model can be derived as

(4) m v ˙ y = F y f + F y r - m v x r I z r ˙ = 2 a F y f - 2 b F y r ,

where Fyf and Fyr represent the type lateral forces of the front wheel and rear wheel respectively, Iz is the vertical inertial moment, r is the yaw rate, m is the mass of the vehicle, vy and vx are the lateral velocity and longitudinal velocity respectively, a is the distance from the front axis to the center of gravity (CG), and b is the distance from the rear axis to the CG. The Fyf and Fyr can be represented by applying the tire model.

To control the vehicle drive within a predetermined trajectory, the path-following model is presented in Fig. 6 (Guo et al., 2018b). The look-ahead point can be expressed as a function concerning the velocity terms. A strategy of adaptive choice of the look-ahead point is proposed by Taghavifar and Rakheja (2019).

https://ms.copernicus.org/articles/12/419/2021/ms-12-419-2021-f06

Figure 6Path-following model.

Download

The dynamic-model-based controller has a better tracking performance than the kinematic-model-based controller in high-speed driving scenarios, for dynamics features of the vehicle are considered, but system complexity is increased. Currently, it is challenging when one single model of vehicle is applied in the vehicle control system to control the system precisely and efficiently. Thus, Yu et al. (2018) and Sun et al. (2017) calculate the yaw rate with a kinematic model, while the steering angle was derived through a dynamics model to make this control system more robust.

As can be seen in Fig. 5, only lateral dynamics of the vehicle are analyzed, in which the longitudinal velocity is set as a constant value for the control system. This is in contrast with practical driving circumstances. It is noteworthy that most research studies on vehicle control design the lateral and longitudinal controller using a separate structure. Consequently, some fatal accidents may occur when only one single controller is utilized due to the lack of adaptation to complicated and fast-changing traffic environments (Lin et al., 2019). To accommodate or eliminate this phenomenon, Li et al. (2016) analyzed the longitudinal dynamics with additional yaw motion dynamics. While Ni and Hu (2017) designed a hierarchical control strategy to simultaneously control lateral and longitudinal dynamics of the vehicle at driving limits. Beal and Boyd (2018) took the longitudinal tire dynamics into consideration in a three-dimensional state portrait, which is an extension of a two-dimensional state portrait. Guo et al. (2018a) added the longitudinal velocity polytope matrix into the lateral dynamics model to make the control system more robust to uncertainties of longitudinal dynamics.

3 Trajectory tracking controller

An appropriate tracking controller with control approaches is required according to the selected model, not only to guarantee high tracking performance but also to keep the high stability of vehicles. After decades of development, there are many control methods for the trajectory tracking of autonomous vehicles, and some of the most used methods are described in this section with state-of-the-art research outcomes. Table 1 illustrates some weaknesses and strengths of each controller. In addition, some optimizations are described for improving on the weaknesses.

Table 1Some weaknesses and strengths of each controller with some optimizations for moderating the weaknesses.

Download Print Version | Download XLSX

3.1 PID

A PID controller is a linear feedback controller widely applied in autonomous vehicles due to its simple structure and features of easy operation and adjustment with a certain robustness. It has the big advantage that it is not necessary to know the mathematical models or the plant compared with other controllers, which helps it maintain good generic applicability (Rupp and Stolz, 2017). Typically, the steering angle of the vehicle can be derived through a traditional PID controller with the following equation (Li et al., 2016):

(5) δ = K P y d - y + K I ( y d - y ) + K D d ( y d - y ) d t ,

where δ is the steering angle, yd is the desired lateral position of reference trajectory, y is the actual lateral position of the vehicle in the global coordinates, and KP, KI, and KD are the proportional, integral, and derivative gain, respectively. Each control gain has its strengths and weaknesses. More details can be found in Farag (2019). Equation (5) illustrates the linear feature of the PID control law, which suggests that it may be unsuitable for a nonlinear system. For instance, vehicles with a PID controller perform badly in cases when the vehicle starts from different initial states (Kanarat, 2004). Abatari and Tafti (2013) proposed a fuzzy PID controller to accommodate this phenomenon; meanwhile, the faster convergence speed without a steady-state tracking error is another advantage of the controller. However, the linear characteristic of the PID controller brings about some problems in updating the PID control gain in real time. Consequently, tuning the control gains automatically and appropriately has become the hardest and most significant part of designing a PID controller (Nie et al., 2018). Lots of methods have been proposed to make this tiresome job easier. some of the most used methods are the fuzzy PID cascade strategy used in Abatari and Tafti (2013), Majid and Arshad (2015), and Yunsheng et al. (2015), the particle swarm optimization (PSO) algorithm in Al-Mayyahi et al. (2015) and Allou and Zennir (2018), and the inverse optimal control technique in Rout and Subudhi (2017). Additionally, some optimization methods for the PID controller have been proposed to improve the PID-based vehicle's tracking performance. For example, a nested PID controller that has a double integral action based on lateral tracking error has been designed by Marino et al. (2011) to make the control system robust to the disturbances on the curvature. A combination of PID controller and a point follow controller is presented in Kolb et al. (2019) to provide a better tracking performance.

3.2 Fuzzy-logic-based controller

PID controllers are linear. Trajectory tracking of autonomous vehicles has high nonlinearity due to the tire forces varying under different road surface conditions (Zhang et al., 2018). The typical model of cars which implied the small-angle law makes the vehicle lack performance and robustness in highly nonlinear scenes such as the high-speed scenario. The proposed controller based on the fuzzy logic law can efficiently alleviate this phenomenon, for the fuzzy controller works well for controlled systems without the complete mathematical model. In addition, fuzzy logic is capable of dealing with many imprecisions and uncertainties of the considered circumstances due to the approximate reasoning feature. Furthermore, the fuzzy logic controller has excellent convergence to the reference path and provides safe and smooth driving (Perez et al., 2009). Lastly, the fuzzy controller has the ability of real-time operation, which increases computational efficiency (Fraichard and Garnier, 2001). Accordingly, the fuzzy-logic-based steering control of autonomous vehicles can achieve a good tracking performance owing to these advantages. Some relevant fuzzy controllers can be found in Riaz and Niazi (2018) and Wang et al. (2015).

Although the fuzzy-logic-based controller possesses the above strength, there is more oscillation of the steering command (Nunes and Bento, 2007), and it is challenging to prove its stability and performance analysis (Attia et al., 2014). The conventional fuzzy logic controller shares the same structure, as can be seen in Fig. 7. It illustrates that the fuzzy logic controller can be modularized as fuzzification, knowledge base, fuzzy inference, and defuzzification. The function of each module of the fuzzy logic controller refers to Allou et al. (2017). However, sharing the same structure is not equivalent to having the same design rules. With the development of technology, they can be very different in many aspects, such as fuzzification/defuzzification methods, fuzzy rules, and fuzzy set definition, decision-making logic, and knowledge base organization (Fraichard and Garnier, 2001). What's more, it is tough work to figure out which one is more suitable for the given problem. Although there are many differences, setting up the fuzzy rule base is the major part of designing a fuzzy controller. For the general autonomous vehicle driving scenario, the input can be set as the state variables of the vehicle concerning the path, while the output is the steering command (Rodriguez-Castaño et al., 2016).

https://ms.copernicus.org/articles/12/419/2021/ms-12-419-2021-f07

Figure 7The fuzzy logic controller.

Download

The linguistic variables and a complete set of expert rules of fuzzy logic can be defined to control the vehicle using the human driving experience, and the vehicle can drive as a human did. To be more specific, the driving experience is expressed as fuzzy rules, in which the variables represent linguistic terms (speed, look ahead distance, etc.). Moreover, the crisp values are replaced by values such as low, middle, and high (Rastelli and Peñas, 2015). These driving experience data can be derived from real human driving experiments (Halin et al., 2018).

Recently, the Takagi–Sugeno (TS) fuzzy system has gained a wide application in vehicle control. The TS fuzzy system is a particular type of fuzzy logic system, in which the consequent part utilizes the affine linear dynamic systems rather than the fuzzy membership function (Takagi and Sugeno, 1985). The TS fuzzy models have become the most used research platform of fuzzy-model-based control because of the remarkable features of the TS fuzzy model for control proposes (Tanaka and Wang, 2004; Nguyen et al., 2018). The gap between fuzzy control and conventional control can be bridged using the local affine (or local linear) models. Additionally, the TS fuzzy controller can be used to illustrate the model of the nonlinear systems widely and efficiently (Rodriguez-Castaño et al., 2016). Consequently, the application in Geng et al. (2009) obtained the slip angle through a fuzzy rule. Taylor's approximation was used to reduce the numeral complexity of the TS fuzzy model in Nguyen et al. (2018) efficiently. The variation of mass and longitudinal velocity of the vehicle was first considered in the lateral dynamic model by Zhang et al. (2018).

3.3 Sliding mode control methods

Sliding mode control (SMC) methods are widely used in nonlinear control systems due to their features. SMC possesses strong robustness to parameter uncertainties and disturbances caused by strong nonlinearity, external disturbances, and complex driving conditions of autonomous vehicles (Wu et al., 2019). Also, the SMC controller can let the vehicle converge to the path quickly (Sun et al., 2019). What's more, SMC has the merits of fast response, insensitivity to parameter variations and disturbances, and simple physical implementation, etc. Moreover, SMC can be integrated with other control algorithms to compensate for the weakness of each other (Norouzi et al., 2018; He et al., 2019). As such, the combination between backstepping and the sliding mode was proposed by He et al. (2019). They proved this method is proficient in disposing of multiple dynamics, nonlinearity, and uncertainty problems.

Despite the SMC controller having an excellent performance in trajectory tracking, it is challenging to utilize in vehicles because the linearization method needs to make the controlled variables always keep close to the reference path (Martin et al., 2013). Moreover, the SMC approach in trajectory tracking will lead to a sizeable lateral acceleration, in which driving in the curvature change of the reference path becomes large (a server double lane change scenario) (Cao et al., 2017). This could be moderated using a preview point strategy as presented in Cao et al. (2017). Furthermore, the most critical problem of SMC is the chattering caused by the switching motion of the sliding surfaces (Wu et al., 2019), depicted in Fig. 8. After decades of development of control science, some useful methods have been proposed to moderate or eliminate this drawback such as STA (Tagne et al., 2014), the fuzzy logic technique (Guo et al., 2017; Norouzi et al., 2018; Shirzadeh et al., 2019), and a variable exponential sliding manifold (Taghavifar and Rakheja, 2019).

https://ms.copernicus.org/articles/12/419/2021/ms-12-419-2021-f08

Figure 8Chattering of SMC.

Download

Some extended SMC controllers were designed to work in different control scenarios such as integral SMC (ISMC) and nonsingular terminal SMC (NTSMC). ISMC has a more flexible structure and keeps the complete robustness or insensitivity for the closed-loop system in the complete response from the initial time instance to the reaching mode (Hu et al., 2019). Since the integral term has been introduced in ISMC for autonomous vehicles, the integral windup may come up. However, few researchers have taken the integral windup into consideration, which may cause the close feedback system to be unstable. Hu et al. (2019) designed a CNF ISMC controller for trajectory tracking considering the integral saturation. In addition, Xu et al. (2017) proposed an anti-windup scheme to solve this phenomenon. Terminal sliding mode control (TSMC) is an extended type of SMC whose sliding upper plane includes nonlinear functions. Therefore, a terminal sliding surface is formulated, and the tracking error on the sliding surface converges to zero in finite time (Liu and Wang, 2012). The NTSMC can achieve faster convergent speed, and the chattering can be reduced (Wu et al., 2019).

3.4 Model predictive control methods

Model predictive control (MPC) is a powerful state feedback controller that utilizes the mathematical model of vehicles to predict the future situation of the vehicle within a limited range of horizons called the prediction horizon. The basic principle of the MPC concept is depicted in Fig. 9; more details are given in J. Liu et al. (2018). MPC is also proficient in dealing with the constrained control problems of the uncertain and nonlinear system due to its capabilities (Attia et al., 2014). Since the constraints are vital for the autonomous vehicle, breaking those constraints may have an undesired consequence such as constraints of rollover prevention, slip control, and lateral stability (Ataei et al., 2019). With the constraint characteristic, MPC has become the most used algorithm to deal with driving limit scenarios. For example, Li et al. (2020) solved the tracking problem of tire–road friction limits by using the MPC controller. What's more, the MPC controller can also handle the problem of a multi-input and multi-output (MIMO) system that might have interactions between their inputs and outputs, which is hard for the PID controller to realize. Moreover, the MPC controller has been regarded as an evolution of the optimal control strategy by solving an optimization problem with penalty functions (cost function) to obtain the inputs which satisfy the desired objectives and constraints over a given time horizon at each time step (Beal and Gerdes, 2012; Kayacan et al., 2018). Considering all the advantages mentioned above, MPC is a natural candidate for the control solutions of trajectory tracking of autonomous vehicles, for it can compute the optimal functions with both soft and hard constraints (Abbas et al., 2017; Wang et al., 2018).

https://ms.copernicus.org/articles/12/419/2021/ms-12-419-2021-f09

Figure 9Basic principle of MPC.

Download

Although MPC has such powerful capabilities, it should be noted that MPC has to solve the problem of online optimization at each sampling time, which requires a powerful CPU and large memory. The relationship between computational capability and system performance is contradictory. The system performance strengthens and the computation is higher when the sample time is short. The computation and system performance decrease when the sample time is long. Moreover, the MPC controller for trajectory tracking of autonomous vehicles will come across very high lateral acceleration when the curvature change of the reference path becomes large (a server double lane change) (Cao et al., 2017).

In general, MPC can be decomposed into linear MPC (LMPC), nonlinear MPC (NMPC), adaptive MPC, and robust MPC (Simotwo et al., 2019b). LMPC does well in tracking fixed operating points, which can be obtained with a linear model (Kayacan et al., 2018). However, the LMPC predicts the future state using a linear time-invariant (LTI) model, which makes the LMPC insensitive to prediction errors. What's more, the tracking performance degrades when the plant is strongly nonlinear due to the LTI prediction accuracy degrade (Franco and Santos, 2019). NMPC utilizes the cost function with a nonlinear mathematic plant model to compute the optimized inputs. At the same time, it satisfies the given constraints, which makes the NMPC efficiently suitable for dealing with the high nonlinearization of dynamic vehicle models. However, the computation is increased due to nonlinearization (Abbas et al., 2017; Kayacan et al., 2018). An autonomous vehicle with an NMPC controller lacks agility because of the high expense computation of NMPC. Some online linearization methods of the nonlinear vehicle model are introduced to overcome this situation such as the linear time-varying (LTV) system (Cao et al., 2019; Guo et al., 2018b) and linear parameter-varying (LPV) system (Pan et al., 2017; Alcala et al., 2018a). Moreover, a TS-MPC controller whose vehicle model is represented using the Takagi–Sugeno (TS) vehicle model and that can reduce the computational time by 10–20 times is proposed by Alcalá et al. (2019). Adaptive MPC uses a fixed model structure, and model parameters are allowed to evolve (Franco and Santos, 2019). Simotwo et al. (2019a) proposed the adaptive MPC and utilized an updated and linearized plant model at each sample time to solve an optimization problem. Robust MPC can not only handle the disturbances, parameters uncertainties, and model errors of vehicles, but can also satisfy the input constraints. A basic robust MPC controller is designed based on the worst-case scenario in Liu et al. (2019). The optimal adaptive MPC is proposed in Zhang et al. (2019) to accommodate the computational burden of robust MPC that possesses many constraints.

Most of the existing research studies utilize a fixed cost function, which is inconsistent with time-varying road conditions. Moreover, a fixed cost function decreases the passenger comfort when the vehicle is far away from the reference trajectory (Wang et al., 2019b). To moderate this phenomenon, the adaptive cost function in the receding optimization process strategy is proposed by Wang et al. (2018). The fuzzy adaptive algorithm was used to adaptively improve the weight of the cost function in Wang et al. (2019b).

3.5 Immersion and invariance

The immersion and invariance (I&I) control algorithm for nonlinear systems was first proposed by Astolfi and Ortega (2003). The I&I control method possesses the capability of both adaptivity and robustness. The robust I&I controller is proficient in solving the disturbances of autonomous vehicles. The I&I adaptive control approach has become an attractive field of research and has many industrial applications (Z. Liu et al., 2018). The I&I controller design does not require the stability proof of Lyapunov functions; thus it is well suited to the scenario where the universal Lyapunov function is often challenging to calculate (Hu and Zhang, 2013). What's more, the I&I controller was tested to be more robust to measurement noise compared with other most used controllers (Calzolari et al., 2017). Although the I&I has superior characteristics compared with the classical adaptive controller, it can not be applied to complex nonlinear systems in a straightforward way (Fujimoto et al., 2010).

The basic principle of the I&I method is to reach the desired control objective by immersing the plant dynamics into a (possibly lower order) target system that captures the desired behavior (Astolfi et al., 2007). By doing that, the sophisticated controller design problem can be reduced into other sub-problems that might be easier to deal with (Talj et al., 2013). To be more specific, a manifold in state space is needed, which can be rendered invariant and attractive, and then the state of the system can reach the manifold by designing a control law (Alia et al., 2015).

Considering all of these features of the I&I, some research studies have applied the I&I controller for the trajectory tracking of autonomous vehicles, such as Talj et al. (2013), Tagne et al. (2013, 2014, 2015a), Alia et al. (2015), Tagne et al. (2015b), and Chebly et al. (2019). The procedure of designing an I&I controller is explained in Astolfi et al. (2007). It can be concluded that the I&I controller has a resemblance to the SMC controller. However, the main difference between SMC and I&I is that the manifold does not need to be reached in I&I, while the manifold must be reached in finite time in SMC (Tagne et al., 2015a). And more parameters need to be tuned compared with the I&I controller. There are some advantages of the I&I compared with SMC: I&I obtains a better generalization. I&I is more flexible in choosing the target dynamics and convergence law toward the dynamics. There is no chattering of I&I. The I&I controller presents more robustness to emergency maneuvers (big turns) (Tagne et al., 2014), and I&I allows us to take greater account of the model in the controller design (Tagne et al., 2015a).

4 Conclusion and development trend

A review of state-of-the-art trajectory tracking of autonomous vehicles is presented in this paper. Lots of trajectory tracking techniques and optimization strategies have been presented in this field, and remarkable results have followed. However, there remain some significant issues that need to be solved.

  1. As the final module of autonomous vehicles, the control performance will be influenced dramatically by the environment perception and path planning modules, such as the perception parameter errors and undesirable trajectory generated by the path planning module. To solve this problem, an MPC controller with integrated local path planning and trajectory control could be used. However, this control strategy is currently in its infancy, and the application scenarios are limited.

  2. Most trajectory control research studies focus on normal driving scenarios at present. Seldom are emergency driving scenarios proposed, and the existing control strategies of emergency driving scenario need a practical emergency driving experiment. An excellent vehicle model with high fidelity and multiple DOFs is required due to the high speed, high nonlinearity, and time-varying characteristics of emergency driving scenarios. What's more, the onboard computer's performance should be good enough to satisfy the real-time requirement. Therefore, further research on the tracking control of emergency scenarios should be proposed.

  3. There are some parameters in the vehicle model that can not be measured by sensors such as road adhesion coefficient and centroid slip angle. Therefore, how to estimate these parameters determines the control performance and robustness. Furthermore, how to realize the stability of the closed-loop system of the combined controller and observer will be an important area of research.

  4. With the development of artificial intelligence and chip processes, using deep learning methods to generate the vehicle model dynamically will be a hot research topic. Artificial intelligence technologies could also be applied in the data drive control under emergency driving scenarios.

  5. In the next few decades, applying one controller can not satisfy the complexity of driving conditions. Using multiple controllers to control the vehicle could be a good strategy. Compared with only one controller, the use of multiple controllers can share the calculation pressure of one controller; the control performance and real-time performance of the control can also be improved. Thus, the strategy with multiple controllers could be achievable in future research.

Code and data availability

No code or data sets were used in this article.

Author contributions

LL surveyed the literature and wrote the paper, JL constructed the overall framework, and SZ drew the figures in the paper.

Competing interests

The authors declare that they have no conflict of interest.

Acknowledgements

The authors thanks the reviewers for their valuable comments and Copernicus Publications for their language and typesetting services.

Financial support

This research has been supported by the National Natural Science Foundation of China (grant no. 51305472) and the Chongqing Postgraduate Joint Training Base (grant no. JDLHPYJD2018003).

Review statement

This paper was edited by Francisco Romero and reviewed by José Ignacio Suárez Marcelo and two anonymous referees.

References

Abatari, H. T. and Tafti, A. D.: Using a fuzzy PID controller for the path following of a car-like mobile robot, in: 2013 First RSI/ISM international conference on robotics and mechatronics (ICRoM), IEEE, Tehran, Iran, 2013. 

Abbas, M. A., Milman, R., and Eklund, J. M.: Obstacle avoidance in real time with nonlinear model predictive control of autonomous vehicles, Can. J. Elect. Comput., 40, 12–22, 2017. 

Al-Mayyahi, A., Wang, W., and Birch, P.: Path tracking of autonomous ground vehicle based on fractional order PID controller optimized by PSO, in: 2015 IEEE 13th International Symposium on Applied Machine Intelligence and Informatics (SAMI), IEEE, Herl'any, Slovakia, 2015. 

Alcala, E., Puig, V., Quevedo, J., and Escobet, T.: Gain-scheduling lpv control for autonomous vehicles including friction force estimation and compensation mechanism, IET Control Theory A., 12, 1683–1693, 2018a. 

Alcala, E., Puig, V., Quevedo, J., Escobet, T., and Comasolivas, R.: Autonomous vehicle control using a kinematic Lyapunov-based technique with LQR-LMI tuning, Control Eng. Pract., 73, 1–12, 2018b. 

Alcalá, E., Puig, V., and Quevedo, J.: TS-MPC for Autonomous Vehicles Including a TS-MHE-UIO Estimator, IEEE T. Veh. Technol., 68, 6403–6413, 2019. 

Alcalá, E., Puig, V., Quevedo, J., and Rosolia, U.: Autonomous racing using Linear Parameter Varying-Model Predictive Control (LPV-MPC), Control Eng. Pract., 95, 104270, https://doi.org/10.1016/j.conengprac.2019.104270, 2020. 

Alia, C., Gilles, T., Reine, T., and Ali, C.: Local trajectory planning and tracking of autonomous vehicles, using clothoid tentacles method, in: 2015 IEEE Intelligent Vehicles Symposium (IV), IEEE, Seoul, Korea (South), 2015. 

Allou, S. and Zennir, Y.: A Comparative Study of PID-PSO and Fuzzy Controller for Path Tracking Control of Autonomous Ground Vehicles, in: ICINCO (1), SCITEPRESS, Porto, Portugal, 2018. 

Allou, S., Zennir, Y., and Belmeguenai, A.: Fuzzy logic controller for autonomous vehicle path tracking, in: 2017 18th International Conference on Sciences and Techniques of Automatic Control and Computer Engineering (STA), IEEE, Monastir, Tunisia, 2017. 

Amer, N. H., Zamzuri, H., Hudha, K., and Kadir, Z. A.: Modelling and control strategies in path tracking control for autonomous ground vehicles: a review of state of the art and challenges, J. Intell. Robot. Syst., 86, 225–254, 2017. 

Amer, N. H., Hudha, K., Zamzuri, H., Aparow, V. R., Abidin, A. F. Z., Kadir, Z. A., and Murrad, M.: Adaptive modified Stanley controller with fuzzy supervisory system for trajectory tracking of an autonomous armoured vehicle, Robot. Auton. Syst., 105, 94–111, https://doi.org/10.1016/j.robot.2018.03.006, 2018. 

Anagnostopoulos, C.-N.: Autonomous Ground Vehicles (Ozguner, U., et al; 2011) [Book review], IEEE Intel. Transp. Sy., 4, 24–26, https://doi.org/10.1109/MITS.2012.2189993, 2012. 

Andersen, H., Chong, Z. J., Eng, Y. H., Pendleton, S., and Ang, M. H.: Geometric path tracking algorithm for autonomous driving in pedestrian environment, in: 2016 IEEE International Conference on Advanced Intelligent Mechatronics (AIM), IEEE, Banff, AB, Canada, 2016. 

Astolfi, A. and Ortega, R.: Immersion and invariance: A new tool for stabilization and adaptive control of nonlinear systems, IEEE T. Autom. Contr., 48, 590–606, 2003. 

Astolfi, A., Karagiannis, D., and Ortega, R.: Nonlinear and adaptive control with applications, Springer Science & Business Media, London, UK, 2007. 

Ataei, M., Khajepour, A., and Jeon, S.: Model Predictive Control for integrated lateral stability, traction/braking control, and rollover prevention of electric vehicles, Vehicle Syst. Dyn., 58, 49–73, https://doi.org/10.1080/00423114.2019.1585557, 2019. 

Attia, R., Orjuela, R., and Basset, M.: Combined longitudinal and lateral control for automated vehicle guidance, Vehicle Syst. Dyn., 52, 261–279, 2014. 

Bacha, S., Saadi, R., Ayad, M. Y., Aboubou, A., and Bahri, M.: A review on vehicle modeling and control technics used for autonomous vehicle path following, in: 2017 International Conference on Green Energy Conversion Systems (GECS), IEEE, Hammamet, Tunisia, 2017. 

Beal, C. E. and Boyd, C.: Coupled lateral-longitudinal vehicle dynamics and control design with three-dimensional state portraits, Vehicle Syst. Dyn., 57, 286–313, https://doi.org/10.1080/00423114.2018.1467019, 2018. 

Beal, C. E. and Gerdes, J. C.: Model predictive control for vehicle stabilization at the limits of handling, IEEE T. Contr. Syst. T., 21, 1258–1269, 2012. 

Buehler, M., Iagnemma, K., and Singh, S.: The 2005 DARPA grand challenge: the great robot race, Springer, Berlin, Heidelberg, Germany, https://doi.org/10.1007/978-3-540-73429-1, 2007. 

Calzolari, D., Schürmann, B., and Althoff, M.: Comparison of trajectory tracking controllers for autonomous vehicles, in: 2017 IEEE 20th International Conference on Intelligent Transportation Systems (ITSC), IEEE, Yokohama, Japan, 2017. 

Cao, H., Song, X., Zhao, S., Bao, S., and Huang, Z.: An optimal model-based trajectory following architecture synthesising the lateral adaptive preview strategy and longitudinal velocity planning for highly automated vehicle, Vehicle Syst. Dyn., 55, 1143–1188, 2017. 

Cao, H., Zhao, S., Song, X., Bao, S., Li, M., Huang, Z., and Hu, C.: An optimal hierarchical framework of the trajectory following by convex optimisation for highly automated driving vehicles, Vehicle Syst. Dyn., 57, 1287–1317, 2019. 

Chebly, A., Talj, R., and Charara, A.: Coupled longitudinal/lateral controllers for autonomous vehicles navigation, with experimental validation, Control Eng. Pract., 88, 79–96, 2019. 

Chen, Y., Shan, Y., Chen, L., Huang, K., and Cao, D.: Optimization of pure pursuit controller based on PID controller and low-pass filter, in: 2018 21st International Conference on Intelligent Transportation Systems (ITSC), IEEE, Maui, HI, USA, 2018. 

Cibooglu, M., Karapinar, U., and Söylemez, M. T.: Hybrid controller approach for an autonomous ground vehicle path tracking problem, in: 2017 25th Mediterranean Conference on Control and Automation (MED), 3–6 July 2017, IEEE, Valletta, Malta, 2017. 

Dixit, S., Fallah, S., Montanaro, U., Dianati, M., Stevens, A., Mccullough, F., and Mouzakitis, A.: Trajectory planning and tracking for autonomous overtaking: State-of-the-art and future prospects, Annu. Rev. Control, 45, 76–86, 2018. 

Domina, A. and Tihanyi, V.: Combined path following controller for autonomous vehicles, Perners Contacts, Pardubice, Czech, Special Issue, 19, 77–84, 2019a. 

Domina, Á. and Tihanyi, V.: Comparison of path following controllers for autonomous vehicles, in: 2019 IEEE 17th World Symposium on Applied Machine Intelligence and Informatics (SAMI), IEEE, Herlany, Slovakia, 2019b. 

Dominguez, S., Ali, A., Garcia, G., and Martinet, P.: Comparison of lateral controllers for autonomous vehicle: Experimental results, in: 2016 IEEE 19th International Conference on Intelligent Transportation Systems (ITSC), IEEE, Rio de Janeiro, Brazil, 2016. 

Drezet, H., Colombel, S., and Avenel, M.-L.: Human-Man Interface Concept For Autonomous Car, in: 2019 IEEE International Conference on Consumer Electronics (ICCE), IEEE, Las Vegas, NV, USA, 2019. 

Elbanhawi, M., Simic, M., and Jazar, R.: Receding horizon lateral vehicle control for pure pursuit path tracking, J. Vib. Control, 24, 619–642, 2018. 

Fang, H., Dou, L., Chen, J., Lenain, R., Thuilot, B., and Martinet, P.: Robust anti-sliding control of autonomous vehicles in presence of lateral disturbances, Control Eng. Pract., 19, 468–478, https://doi.org/10.1016/j.conengprac.2011.01.008, 2011. 

Farag, W.: Complex Trajectory Tracking Using PID Control for Autonomous Driving, Int. J. ITS Res., 18, 356–366, https://doi.org/10.1007/s13177-019-00204-2, 2020. 

Fraichard, T. and Garnier, P.: Fuzzy control to drive car-like vehicles, Robot. Auton. Syst., 34, 1–22, 2001. 

Franco, A. and Santos, V.: Short-term path planning with multiple moving obstacle avoidance based on adaptive MPC, in: 2019 IEEE International Conference on Autonomous Robot Systems and Competitions (ICARSC), IEEE, Porto, Portugal, 2019. 

Fujimoto, K., Yokoyama, M., and Tanabe, Y.: I&I-based adaptive control of a four-rotor mini helicopter, in: IECON 2010-36th Annual Conference on IEEE Industrial Electronics Society, IEEE, Glendale, AZ, USA, 2010. 

Geng, C., Mostefai, L., Denaï, M., and Hori, Y.: Direct yaw-moment control of an in-wheel-motored electric vehicle based on body slip angle fuzzy observer, IEEE T. Ind. Electron., 56, 1411–1419, 2009. 

Guo, H., Cao, D., Chen, H., Sun, Z., and Hu, Y.: Model predictive path following control for autonomous cars considering a measurable disturbance: Implementation, testing, and verification, Mech. Syst. Signal Pr., 118, 41–60, https://doi.org/10.1016/j.ymssp.2018.08.028, 2019. 

Guo, J., Luo, Y., and Li, K.: An adaptive hierarchical trajectory following control approach of autonomous four-wheel independent drive electric vehicles, IEEE T. Intell. Transp., 19, 2482–2492, 2017. 

Guo, J., Luo, Y., and Li, K.: Robust gain-scheduling automatic steering control of unmanned ground vehicles under velocity-varying motion, Vehicle Syst. Dyn., 57, 595–616, https://doi.org/10.1080/00423114.2018.1475677, 2018a. 

Guo, J., Luo, Y., Li, K., and Dai, Y.: Coordinated path-following and direct yaw-moment control of autonomous electric vehicles with sideslip angle estimation, Mech. Syst. Signal Pr., 105, 183–199, https://doi.org/10.1016/j.ymssp.2017.12.018, 2018b. 

Halin, H., Khairunizam, W., Ikram, K., Haris, H., Zunaidi, I., Bakar, S., Razlan, Z., and Desa, H.: Design Simulation of a Fuzzy Steering Wheel Controller for a buggy car, in: 2018 International Conference on Intelligent Informatics and Biomedical Sciences (ICIIBMS), 2018. 

He, X., Liu, Y., Lv, C., Ji, X., and Liu, Y.: Emergency steering control of autonomous vehicle for collision avoidance and stabilisation, Vehicle Syst. Dynam., 57, 1163–1187, 2019. 

Hu, C., Wang, Z., Taghavifar, H., Na, J., Qin, Y., Guo, J., and Wei, C.: MME-EKF-based path-tracking control of autonomous vehicles considering input saturation, IEEE T. Veh. Technol., 68, 5246–5259, 2019. 

Hu, J. and Zhang, H.: Immersion and invariance based command-filtered adaptive backstepping control of VTOL vehicles, Automatica, 49, 2160–2167, 2013. 

Kaltenhäuser, B., Werdich, K., Dandl, F., and Bogenberger, K.: Market development of autonomous driving in Germany, Trans. Res. A-Pol., 132, 882–910, https://doi.org/10.1016/j.tra.2020.01.001, 2020. 

Kanarat, A.: Motion Planning and Robust Control for Nonholonomic Mobile Robots under Uncertainties, PhD thesis, Virginia Polytechnic Institute and State University, USA, 149 pp., available at: http://hdl.handle.net/10919/28316 (last access: 15 April 2021), 2004. 

Kanchwala, H.: Path Planning and Tracking of an Autonomous Car With High Fidelity Vehicle Dynamics Model and Human Driver Trajectories, in: 2019 IEEE 10th International Conference on Mechanical and Aerospace Engineering (ICMAE), IEEE, Brussels, Belgium, 2019. 

Kayacan, E., Ramon, H., and Saeys, W.: Robust Trajectory Tracking Error-Based Model Predictive Control for Unmanned Ground Vehicles, IEEE/ASME Transactions on Mechatronics, 21, 1–1, https://doi.org/10.1109/TMECH.2015.2492984, 2015. 

Kayacan, E., Ramon, H., and Saeys, W.: Robust Trajectory Tracking Error Model-Based Predictive Control for Unmanned Ground Vehicles, IEEE/ASME Transactions on Mechatronics, 21, 806–814, https://doi.org/10.1109/TMECH.2015.2492984, 2018. 

Kolb, J. K., Nitzsche, G., and Wagner, S.: A simple yet efficient Path Tracking Controller for Autonomous Trucks, IFAC-PapersOnLine, 52, 307–312, 2019. 

Kuutti, S., Bowden, R., Jin, Y., Barber, P., and Fallah, S.: A Survey of Deep Learning Applications to Autonomous Vehicle Control, IEEE T. Intell. Transp., 22, 712–733, https://doi.org/10.1109/TITS.2019.2962338, 2021. 

Ley-Rosas, J. J., González-Jiménez, L. E., Loukianov, A. G., and Ruiz-Duarte, J. E.: Observer based sliding mode controller for vehicles with roll dynamics, J. Frankl. Inst., 356, 2559–2581, https://doi.org/10.1016/j.jfranklin.2018.11.031, 2019. 

Li, B., Du, H., and Li, W.: Trajectory control for autonomous electric vehicles with in-wheel motors based on a dynamics model approach, IET Intell. Transp. Sy., 10, 318–330, 2016. 

Li, H., Luo, J., Yan, S., Zhu, M., Hu, Q., and Liu, Z.: Research on Parking Control of Bus Based on Improved Pure Pursuit Algorithms, in: 2019 18th International Symposium on Distributed Computing and Applications for Business Engineering and Science (DCABES), IEEE, Wuhan, China, 2019. 

Li, S. E., Chen, H., Li, R., Liu, Z., Wang, Z., and Xin, Z.: Predictive lateral control to stabilise highly automated vehicles at tire-road friction limits, Vehicle Syst. Dyn., 58, 768–786, 2020. 

Li, Z., Wang, B., Gong, J., Gao, T., Lu, C., and Wang, G.: Development and evaluation of two learning-based personalized driver models for pure pursuit path-tracking behaviors, in: 2018 IEEE Intelligent Vehicles Symposium (IV), IEEE, Changshu, China, 2018. 

Lin, F., Zhang, Y., Zhao, Y., Yin, G., Zhang, H., and Wang, K.: Trajectory Tracking of Autonomous Vehicle with the Fusion of DYC and Longitudinal–Lateral Control, Chin. J. Mech. Eng., 32, https://doi.org/10.1186/s10033-019-0327-9, 2019. 

Liu, J. and Wang, X.: Advanced sliding mode control for mechanical systems, Springer, Beijing, China, 2012. 

Liu, J., Jayakumar, P., Stein, J. L., and Ersal, T.: A nonlinear model predictive control formulation for obstacle avoidance in high-speed autonomous ground vehicles in unstructured environments, Vehicle Syst. Dyn., 56, 853–882, 2018. 

Liu, J., Jayakumar, P., Stein, J. L., and Ersal, T.: Improving the robustness of an MPC-based obstacle avoidance algorithm to parametric uncertainty using worst-case scenarios, Vehicle Syst. Dyn., 57, 874–913, 2019. 

Liu, Z., Yuan, R., Fan, G., and Yi, J.: Immersion and invariance based composite adaptive control of nonlinear high-order systems, in: 2018 Chinese Control And Decision Conference (CCDC), IEEE, Shenyang, China, 2018. 

Majid, M. and Arshad, M.: A fuzzy self-adaptive PID tracking control of autonomous surface vehicle, in: 2015 IEEE International Conference on Control System, Computing and Engineering (ICCSCE), 2015. 

Marino, R., Scalzi, S., and Netto, M.: Nested PID steering control for lane keeping in autonomous vehicles, Control Engineering Practice, 19, 1459–1467, 2011. 

Martin, T. C., Orchard, M. E., and Sánchez, P. V.: Design and simulation of control strategies for trajectory tracking in an autonomous ground vehicle, IFAC Proceedings Volumes, 46, 118–123, 2013. 

Nguyen, A.-T., Sentouh, C., and Popieul, J.-C.: Fuzzy steering control for autonomous vehicles under actuator saturation: Design and experiments, J. Frankl. Inst., 355, 9374–9395, 2018. 

Ni, J. and Hu, J.: Dynamics control of autonomous vehicle at driving limits and experiment on an autonomous formula racing car, Mech. Syst. Signal Pr., 90, 154–174, https://doi.org/10.1016/j.ymssp.2016.12.017, 2017. 

Nie, L., Guan, J., Lu, C., Zheng, H., and Yin, Z.: Longitudinal speed control of autonomous vehicle based on a self-adaptive PID of radial basis function neural network, IET Intell. Transp. Sy., 12, 485–494, 2018. 

Norouzi, A., Kazemi, R., and Azadi, S.: Vehicle lateral control in the presence of uncertainty for lane change maneuver using adaptive sliding mode control with fuzzy boundary layer, P. I. Mech. Eng. I-J. Sys., 232, 12–28, 2018. 

Nunes, U. and Bento, L. C.: Data fusion and path-following controllers comparison for autonomous vehicles, Nonlinear Dynam., 49, 445–462, 2007. 

Pan, S., Bolin, G., Shugang, X., and Rui, F.: Optimal predictive control for path following of a full drive-by-wire vehicle at varying speeds, Chin. J. Mech. Eng., 30, 711–721, 2017. 

Park, M., Lee, S., and Han, W.: Development of Steering Control System for Autonomous Vehicle Using Geometry-Based Path Tracking Algorithm, ETRI J., 37, 617–625, https://doi.org/10.4218/etrij.15.0114.0123, 2015. 

Pereira, G. C., Svensson, L., Lima, P. F., and Mårtensson, J.: Lateral model predictive control for over-actuated autonomous vehicle, in: 2017 IEEE Intelligent Vehicles Symposium (IV), IEEE, Los Angeles, CA, USA, 2017. 

Perez, J., Gonzalez, C., Milanes, V., Onieva, E., Godoy, J., and Pedro, T. d.: Modularity, adaptability and evolution in the AUTOPIA architecture for control of autonomous vehicles, in: 2009 IEEE International Conference on Mechatronics, 14–17 April 2009, IEEE, Malaga, Spain, 2009. 

Raffo, G. V., Gomes, K., Normey-Rico, J., Kelber, C., and Becker, L.: A Predictive Controller for Autonomous Vehicle Path Tracking, IEEE T. Intell. Trans., 10, 92–102, https://doi.org/10.1109/TITS.2008.2011697, 2009. 

Rajamani, R.: Vehicle dynamics and control, Springer Science & Business Media, USA, https://doi.org/10.1007/978-1-4614-1433-9, 2011. 

Rastelli, J. P. and Peñas, M. S.: Fuzzy logic steering control of autonomous vehicles inside roundabouts, Appl. Soft Comput., 35, 662–669, 2015. 

Riaz, F. and Niazi, M. A.: Enhanced emotion enabled cognitive agent-based rear-end collision avoidance controller for autonomous vehicles, Simulation, 94, 957–977, 2018. 

Rodriguez-Castaño, A., Heredia, G., and Ollero, A.: High-speed autonomous navigation system for heavy vehicles, Appl. Soft Comput., 43, 572–582, 2016. 

Rotondo, D., Puig, V., Nejjari, F., and Witczak, M.: Automated generation and comparison of Takagi–Sugeno and polytopic quasi-LPV models, Fuzzy Set. Syst., 277, 44–64, 2015. 

Rout, R. and Subudhi, B.: Inverse optimal self-tuning PID control design for an autonomous underwater vehicle, Int. J. Sys. Sci., 48, 367–375, 2017. 

Rupp, A. and Stolz, M.: Survey on control schemes for automated driving on highways, in: Automated driving, Springer, Cham, Switzerland, 43–69, https://doi.org/10.1007/978-3-319-31895-0_4, 2017. 

SAE On-Road Automated Vehicle Standards Committee: Taxonomy and definitions for terms related to on-road motor vehicle automated driving systems, SAE Standard J, 3016, 1–16, 2014. 

Shirzadeh, M., Shojaeefard, M. H., Amirkhani, A., and Behroozi, H.: Adaptive fuzzy nonlinear sliding-mode controller for a car-like robot, in: 2019 5th Conference on Knowledge Based Engineering and Innovation (KBEI), IEEE, Tehran, Iran, 2019. 

Simotwo, J. C., Kamau, S. I., and Hinga, P. K.: Adaptive Control Strategy to Steer and Drive an Autonomous 4ws4wd Ground Vehicle, in: Proceedings of Sustainable Research and Innovation Conference, CNR-IRCRES, Rome, Italy, 2019a. 

Simotwo, J. C., Kamau, S. I., and Hinga, P. K.: Control Strategies to Steer and Drive an Autonomous 4WS4WDGround Vehicle: A Review of MPC Approaches, in: Proceedings of Sustainable Research and Innovation Conference, CNR-IRCRES, Rome, Italy, 2019b. 

Snider, J. M.: Automatic Steering Methods for Autonomous Automobile Path Tracking, thesis, Carnegie Mellon University, Pittsburgh, Pennsylvania, USA, 78 pp., 2006. 

Sun, H., Zhang, C., An, G., Chen, Q., and Liu, C.: Fuzzy-model-based H8 dynamic output feedback control with feedforward for autonomous vehicle path tracking, in: 2017 International Conference on Fuzzy Theory and Its Applications (iFUZZY), IEEE, Pingtung, Taiwan, 2017. 

Sun, Z., Zheng, J., Man, Z., Fu, M., and Lu, R.: Nested adaptive super-twisting sliding mode control design for a vehicle steer-by-wire system, Mech. Syst. Signal Pr., 122, 658–672, 2019. 

Taghavifar, H. and Rakheja, S.: Path-tracking of autonomous vehicles using a novel adaptive robust exponential-like-sliding-mode fuzzy type-2 neural network controller, Mech. Syst. Signal Pr., 130, 41–55, https://doi.org/10.1016/j.ymssp.2019.04.060, 2019. 

Tagne, G., Talj, R., and Charara, A.: Immersion and invariance control for reference trajectory tracking of autonomous vehicles, in: 16th International IEEE Conference on Intelligent Transportation Systems (ITSC 2013), IEEE, The Hague, the Netherlands, 2013. 

Tagne, G., Talj, R., and Charara, A.: Immersion and invariance vs sliding mode control for reference trajectory tracking of autonomous vehicles, in: 2014 European Control Conference (ECC), IEEE, Strasbourg, France, 2014. 

Tagne, G., Talj, R., and Charara, A.: Design and validation of a robust immersion and invariance controller for the lateral dynamics of intelligent vehicles, Control Eng. Pract., 40, 81–92, 2015a. 

Tagne, G., Talj, R., and Charara, A.: Design and comparison of robust nonlinear controllers for the lateral dynamics of intelligent vehicles, IEEE T. Intell. Transp., 17, 796–809, 2015b. 

Takagi, T. and Sugeno, M.: Fuzzy identification of systems and its applications to modeling and control, IEEE Transactions on Systems, Man, and Cybernetics, SMC-15, 116–132, https://doi.org/10.1109/TSMC.1985.6313399, 1985. 

Talj, R., Tagne, G., and Charara, A.: Immersion and invariance control for lateral dynamics of autonomous vehicles, with experimental validation, in: 2013 European Control Conference (ECC), IEEE, Zurich, Switzerland, 2013. 

Tanaka, K. and Wang, H. O.: Fuzzy control systems design and analysis: a linear matrix inequality approach, John Wiley & Sons, USA, https://doi.org/10.1002/0471224596, 2004. 

Tang, L., Yan, F., Zou, B., Wang, K., and Lv, C.: An Improved Kinematic Model Predictive Control for High-Speed Path Tracking of Autonomous Vehicles, IEEE Access, 8, 51400–51413, 2020. 

Van Brummelen, J., O'Brien, M., Gruyer, D., and Najjaran, H.: Autonomous vehicle perception: The technology of today and tomorrow, Transport. Res. C-Emer., 89, 384–406, https://doi.org/10.1016/j.trc.2018.02.012, 2018. 

Wang, H., Chen, X., Chen, Y., Li, B., and Miao, Z.: Trajectory Tracking and Speed Control of Cleaning Vehicle Based on Improved Pure Pursuit Algorithm, in: 2019 Chinese Control Conference (CCC), IEEE, Guangzhou, China, 2019a. 

Wang, H., Liu, B., Ping, X., and An, Q.: Path Tracking Control for Autonomous Vehicles Based on an Improved MPC, IEEE Access, 7, 161064–161073, 2019b. 

Wang, X., Fu, M., Ma, H., and Yang, Y.: Lateral control of autonomous vehicles based on fuzzy logic, Control Eng. Pract., 34, 1–17, 2015.  

Wang, X., Guo, L., and Jia, Y.: Road Condition Based Adaptive Model Predictive Control for Autonomous Vehicles, in: ASME 2018 Dynamic Systems and Control Conference, 2018. 

Wu, N., Huang, W., Song, Z., Wu, X., Zhang, Q., and Yao, S.: Adaptive dynamic preview control for autonomous vehicle trajectory following with DDP based path planner, in: 2015 IEEE Intelligent Vehicles Symposium (IV), 28 June–1 July 2015, IEEE, Seoul, Korea (South), 2015. 

Wu, Y., Wang, L., Zhang, J., and Li, F.: Path following control of autonomous ground vehicle based on nonsingular terminal sliding mode and active disturbance rejection control, IEEE T. Veh. Technol., 68, 6379–6390, 2019. 

Xu, D., Shi, Y., and Ji, Z.: Model-free adaptive discrete-time integral sliding-mode-constrained-control for autonomous 4WMV parking systems, IEEE T. Ind. Electron., 65, 834–843, 2017. 

Yang, J., Bao, H., Ma, N., and Xuan, Z.: An algorithm of curved path tracking with prediction model for autonomous vehicle, in: 2017 13th International Conference on Computational Intelligence and Security (CIS), IEEE, Hong Kong, China, 2017. 

Yu, Z., Zhang, R., Xiong, L., and Fu, Z.: Robust hierarchical controller with conditional integrator based on small gain theorem for reference trajectory tracking of autonomous vehicles, Vehicle Syst. Dyn., 57, 1143–1162, https://doi.org/10.1080/00423114.2018.1555333, 2018. 

Yunsheng, F., Xiaojie, S., Guofeng, W., and Chen, G.: On fuzzy self-adaptive PID control for USV course, in: 2015 34th Chinese Control Conference (CCC), IEEE, Hangzhou, China, 2015. 

Zhang, C., Hu, J., Qiu, J., Yang, W., Sun, H., and Chen, Q.: A novel fuzzy observer-based steering control approach for path tracking in autonomous vehicles, IEEE T. Fuzzy Syst., 27, 278–290, 2018. 

Zhang, H. and Braun, S. G.: Signal processing and control challenges for smart vehicles, Mech. Syst. Signal Pr., 87, 1–3, https://doi.org/10.1016/j.ymssp.2016.11.016, 2017. 

Zhang, K., Liu, C., and Shi, Y.: Computationally efficient adaptive model predictive control for constrained linear systems with parametric uncertainties, in: 2019 IEEE 28th International Symposium on Industrial Electronics (ISIE), IEEE, Vancouver, BC, Canada, 2019. 

Zhang, X., and Zhu, X.: Autonomous path tracking control of intelligent electric vehicles based on lane detection and optimal preview method, Expert Syst. Appl., 121, 38–48, 2019. 

Zhu, Q., Huang, Z., Liu, D., and Dai, B.: An adaptive path tracking method for autonomous land vehicle based on neural dynamic programming, in: 2016 IEEE International Conference on Mechatronics and Automation, IEEE, Harbin, China, 2016. 

Zou, Y., Li, L., Tang, X., Ye, J., and Yu, L.: Double Arc Path Tracking Control of Driverless Vehicle Based on Time Delay Dynamic Prediction, in: 2018 37th Chinese Control Conference (CCC), IEEE, Wuhan, China, 2018. 

Download
Short summary
This paper reviews the state-of-the-art trajectory tracking of autonomous vehicles. Autonomous vehicles have become more and more popular with the development of artificial intelligence and automatic control. If you have any interest in the trajectory tracking of autonomous vehicles, this paper is the one that you can not miss. It will give you a brief concept of the current development of the trajectory tracking of autonomous vehicles.