Next Article in Journal
Irradiance Restoration Based Shadow Compensation Approach for High Resolution Multispectral Satellite Remote Sensing Images
Previous Article in Journal
Measuring Transverse Displacements Using Unmanned Aerial Systems Laser Doppler Vibrometer (UAS-LDV): Development and Field Validation
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Design, Validation and Comparison of Path Following Controllers for Autonomous Vehicles

1
School of Automotive Studies, Tongji University, Shanghai 201804, China
2
Clean Energy Automotive Engineering Center, Tongji University, Shanghai 201804, China
3
Postdoctoral Station of Mechanical Engineering, Tongji University, Shanghai 201804, China
*
Author to whom correspondence should be addressed.
Sensors 2020, 20(21), 6052; https://doi.org/10.3390/s20216052
Submission received: 27 September 2020 / Revised: 21 October 2020 / Accepted: 22 October 2020 / Published: 24 October 2020
(This article belongs to the Section Intelligent Sensors)

Abstract

:
As one of the core issues of autonomous vehicles, vehicle motion control directly affects vehicle safety and user experience. Therefore, it is expected to design a simple, reliable, and robust path following the controller that can handle complex situations. To deal with the longitudinal motion control problem, a speed tracking controller based on sliding mode control with nonlinear conditional integrator is proposed, and its stability is proved by the Lyapunov theory. Then, a linear parameter varying model predictive control (LPV-MPC) based lateral controller is formulated that the optimization problem is solved by CVXGEN. The nonlinear active disturbance rejection control (ADRC) method is applied to the second lateral controller that is easy to be implemented and robust to parametric uncertainties and disturbances, and the pure pursuit algorithm serves as a benchmark. Simulation results in different scenarios demonstrate the effectiveness of the proposed control schemes, and a comparison is made to highlight the advantages and drawbacks. It can be concluded that the LPV-MPC has some trouble to handle uncertainties while the nonlinear ADRC performs slight worse tracking but has strong robustness. With the parallel development of the control theory and computing power, robust MPC may be the future direction.

1. Introduction

Autonomous driving technology has become a research and development hotspot recently, since it has great potential to improve active safety, alleviate traffic congestion, and reduce energy consumption [1,2]. It was reported that the driver’s mistakes contribute entirely or partially to nearly 90% of road accidents [3]. The autonomous system is more reliable and faster to react than human drivers, so it can handle critical scenarios that human drivers find challenging or lack the ability to navigate, such as emergency obstacle avoidance [4]. On the other hand, under the perspective of networked control, the platooning of autonomous vehicles provides an effective way to increase traffic capacity and fuel efficiency [5]. Therefore, numerous contests of autonomous vehicles have been carried out to promote technological development, such the DARPA (Defense Advanced Research Projects Agency) Challenges in the USA [6] and the Intelligent Vehicle Future Challenges in China [7], etc. Simultaneously, the research of autonomous vehicles is booming and highly competitive in the industry. The Waymo and Cruise autonomous driving cars are typical commercial products that have attracted wide attention [8].
The key technologies of autonomous vehicles consist of environment perception, decision making, motion planning, and vehicle motion control, and the objective of vehicle motion control can be divided into path stabilization and trajectory stabilization [1]. The difference between them is that the reference trajectory is independent of time in the path following problem, while the trajectory tracking is related to time. In this paper, we focus on the path following issue of autonomous vehicles, which manipulates steering wheel to guide the vehicle to track a desired path. The path can be generated offline based on a priori or online through a high-level planning layer. The objective of path following is to realize accurate and smooth tracking while the vehicle stability is guaranteed. Besides, robustness is also a key issue in control design considering the high nonlinearity of the vehicle dynamics and the parametric uncertainties and disturbances. Many algorithms have been applied to deal with path following, including the pure pursuit method (PPM) [9], sliding mode control (SMC) [10,11], and model predictive control (MPC) [12,13,14], etc. However, there are still some challenges for practical real-time implementation although the previous research achievements were successful to some extent. For instance, MPC controllers may suffer from heavy computational burden due to online optimization, especially for the nonlinear MPC. Moreover, it is difficult to accurately model the vehicle dynamics at the handling limits. On the other hand, make everything as simple as possible is necessary for implementation in practice. Therefore, it is expected to design a simple, reliable, and robust path tracking controller.
In this paper, we design, validate, and compare three path following schemes to track a predetermined path, using linear parameter varying model predictive control, nonlinear active disturbance rejection control [15], and the pure pursuit method, respectively. The main contributions of this paper are summarized as follows:
  • A longitudinal speed controller based on sliding mode control with nonlinear conditional integrator is proposed to realize the longitudinal motion control of autonomous vehicle during the path following process. It is well known that sliding mode controllers suffer from chattering. To solve this problem, we adopt the saturation function to replace the sign function, meanwhile, a nonlinear integral action is introduced to achieve zero steady-state error and improve the transient performance, which can also avoid integral divergence. Stability analysis is given to prove that the equilibrium point is globally asymptotically stable.
  • The lateral controllers based on LPV-MPC (Linear Parameter Varying Model Predictive Control), ADRC (Active Disturbance Rejection Control), and PPM (Pure Pursuit Method)are designed, respectively. First, because the MPC can exploit available preview information and handles constraints, an MPC lateral control-based strategy that considers the soft constraints of the sideslip angle of the steer wheel is formulated based on the error dynamics model, which adopts the CVXGEN [16] solver to improve computational efficiency. Second, the nonlinear ADRC is applied to develop the lateral controller due to the simple control structure and good robustness, which is also largely model independent. Finally, the pure pursuit method using the geometric model is provided as a benchmark.
  • Multiple simulations in different scenarios are conducted to validate the effectiveness and capability of the proposed longitudinal speed controller and lateral path following controllers. A comparison of the three mentioned lateral controllers is made to highlight the advantages and drawbacks of each approach in path following. Finally, the possible development direction in the future is given.
The rest of this paper is organized as follows: Section 2 introduces the state of the art. Section 3 presents the system model and the problem definition. Section 4 explains the design procedure for the longitudinal speed controller. Section 5 presents the lateral controllers design of LPV-MPC, ADRC, and PPM, respectively. Section 6 shows the results and analysis. Finally, the paper is concluded in Section 7.

2. Related Work

Extensive work has been done to vehicle motion control of autonomous vehicles. In this section, we provide a brief review of the state of the art. Vehicle motion control can be divided into longitudinal control and lateral control. Further, lateral control methods can be divided into geometry based, kinematics based, and dynamics based.
The longitudinal control manipulates drive and brake actuators to guide the autonomous vehicle to track a desired speed profile. The main control methods can be roughly classified into three categories: (1) Model-free control. The system dynamics are regarded as a black-box, and the control commands are generated from tracking errors only, e.g., the proportional-integral-derivative (PID) design [17]. (2) Model-based feedback control. A discrete-time preview speed controller was developed considering future desired speed and road slope information, which holds the advantage of prediction and to reduce to computational load as well compared to MPC [18]. Gerdes et al. utilized a multiple-surface sliding mode control to realize speed and space control [19]. To improve tracking performance under model uncertainties and external disturbances, a time-varying parameter adaptive speed control algorithm is proposed [20]. (3) Model-based optimization. The model predictive control framework was applied in a 16-bit micro controller, which can exploit available preview information [21]. However, it may suffer from high computational load, especially for the nonlinear MPC. Improving the computational efficiency is a key issue for MPC application.
The lateral control manipulates the steering actuator to deal with the path following problem generally, and the direct yaw moment control can be used as an additional approach for distributed drive vehicles and vehicles equipped with differential braking. According to the difference of the system model, path tracking control methods can be roughly classified into three categories: (1) Geometry based. It used the geometric relationship between the vehicle and reference. Classical algorithms include the pure pursuit method and Stanley algorithm [17], which were used in the DARPA Challenge vehicle. Such methods are simple and work well in many situations, but may have trouble on tight corners and at high speed due to a lack of consideration for vehicle dynamics. (2) Kinematics based. It is usually assumed that the autonomous vehicle satisfies non-holonomic constraint, in other words, the side slip angle is assumed to be zero. Aiming at the path tracking problem of the non-holonomic mobile robot, the kinematics model is transformed into the chain type by state and input feedback transformation, and a smooth time-varying feedback control law was given [9]. (3) Dynamics based. In order to obtain higher precision under the conditions of high speed and large curvature, it is necessary to consider the vehicle dynamics in the control design. A nested PID steering control scheme was proposed that the outer loop is used to compute yaw rate reference based on lateral offset and then the inner loop tracks the desired yaw rate [22]. Xu et al. presented a preview steering control algorithm, which formulated the path tracking issue as an augmented optimal control problem with dynamic disturbance [23]. Tagne et al. analyzed and compared three lateral nonlinear adaptive controllers, including the higher order sliding mode controller, the immersion and invariance controller, and the passivity-based controller [24]. MPC has become a popular technique that enables the vehicle to act ahead of time and handle constraints more conveniently. Falcone et al. demonstrated the effectiveness of linear MPC-based steering controller with a speed up to 21 m/s on a slippery road [25], and proposed a control scheme by a combined use of breaking and steering [26]. The integration of path tracking, vehicle stabilization, and collision avoidance had been investigated by considering stability envelope and environmental envelope in state and output constraints of MPC [27,28]. To safely navigate highly dynamic scenarios, the nonlinear model predictive controller also had been designed and validated [29]. It should be noted that appropriate tradeoffs between model fidelity and computation should be solved with caution [30]. Hu et al. [31] proposed a robust H output-feedback control strategy considering the parametric uncertainties and external disturbances. For the similar purpose, a linear active disturbance rejection control scheme is proposed for lane keeping problem [32]. Compared to this work, the nonlinear active disturbance rejection is used in this paper to improve the transient performance.

3. Systems Description

In order to describe the motion of an autonomous vehicle, the system dynamics of path following is defined, as illustrated in Figure 1. A preview lateral model is utilized here, where p c is the preview control point and p d is the reference path point.

3.1. Longitudinal Vehicle Dynamics

Considering a vehicle moving on an inclined road, a force balance along the vehicle longitudinal axis yields:
m ( v ˙ x v y γ ) = F x F y f sin δ f F r F w F g ,
where m is the vehicle mass, v x and v y are the vehicle longitudinal and lateral velocities, γ is the vehicle yaw rate, F x is the total tire force along the vehicle longitudinal axis, F y f is the lateral tire force of the front steering wheel, δ f is the front wheel steering angle, F r is the rolling resistance force, F w is the aerodynamic force, and F g is the gravitational force component generated by road grade.
The wheel dynamics can be expressed as the following equation:
I ω ω ˙ i j = T i j F x i j R , i j = f l , f r , r l , r r ,
where I ω is the wheel inertia, ω i j is the wheel angular velocity and the subscript represents the four wheel of the vehicle, F x i j is the longitudinal tire force, R is the wheel rolling radius.

3.2. Lateral Vehicle Dynamics

The objective of lateral control design is to eliminate the path error while guaranteeing vehicle stability. As shown in Figure 1, it is desirable to both eliminate the lateral error y e and heading angle error φ e at the preview point by manipulating the control input steering angle δ f .
The preview lateral kinematics can be modeled as:
{ y ˙ e = v x φ e v x β l p γ φ ˙ e = v x κ γ ,
where β is the sideslip angle, l p is the preview distance, κ is the path curvature.
The 2DOF vehicle dynamics model is used to design the lateral controller, which can be expressed as:
{ β ˙ = 2 ( C α f + C α r ) m v x β + ( 2 ( C α f l f C α r l r ) m v x 2 1 ) γ + 2 C α f m v x δ f γ ˙ = 2 ( C α f l f C α r l r ) I z β + 2 ( C α f l f 2 + C α r l r 2 ) I z v x γ + 2 C α f l f I z δ f ,
where C α f and C α r denote the cornering stiffness of the single front tire and rear tire, I z is the yaw moment of inertia, l f and l r are the distance from the front axle and rear axle to the center of gravity, respectively.
The combined dynamics (3) and (4) can be written in the state space form, with the states x = [ y e φ e β γ ] T 4 , the control input u = δ f , the system outputs y = [ y e φ e ] T 2 , and the measurable external disturbance w = κ ( t ) :
x ˙ = A x + B u + D w y = C x ,
in which:
A = [ 0 v x v x l p 0 0 0 1 0 0 2 ( C α f + C α r ) m v x 2 ( C α f l f C α r l r ) m v x 2 1 0 0 2 ( C α f l f C α r l r ) I z 2 ( C α f l f 2 + C α r l r 2 ) I z v x ] , B = [ 0 0 0 0 2 C α f m v x 0 2 C α f l f I z 1 I z ] C = [ 1 0 0 1 0 0 0 0 ] , D = [ 0 v x 0 0 ] .

4. Longitudinal Speed Controller Design

The objective of longitudinal speed control is to track the desired speed profile accurately and smoothly, by manipulating the motor and electro-hydraulic brake system (EHB) in this paper. To improve the robustness to parametric uncertainties and provide disturbance rejection, a speed tracking controller via sliding mode control with nonlinear conditional integrator is developed. The control framework is shown in Figure 2.
From the control block diagram in Figure 3, it can be seen that the longitudinal speed controller consists of feedforward and feedback components. The feedforward term uses the desired acceleration profile to calculate the acceleration resistance, and compensates the road resistance according to vehicle operating conditions simultaneously. In the feedback control term, the sliding mode control method is adopted. Note that integral action is introduced in the sliding mode controller to ensure asymptotic tracking.

4.1. Feedforward of Speed Controller

4.1.1. Feedforward from Reference Acceleration

According to the desired longitudinal acceleration a d at the reference point generated offline or provided by high-level planner, feedforward longitudinal force from reference acceleration F x f f can be calculated from Newton’s second law as follows:
F x f f = m a d .

4.1.2. Drag Compensation

As shown in Equation (1), the road resistance concludes the resistance force from the vehicle’s rolling F r , aerodynamic force F w , road grade F g , and the longitudinal component from the front axle turning F t . The expression of each resistance is given as follows:
F r = m g f F w = C D A v x 2 21.15 F g = m g sin θ g F t = F y f sin δ f m l f | a y tan δ f | l ,
where f is the rolling resistance coefficient, C D is the air resistance coefficient, A is the frontal area of the vehicle, θ g is the road grade measured or estimated, a y is the lateral acceleration. The calculation of F t uses a steady state assumption and assumes that the front lateral force is proportional to the front static vertical load.
Then, the drag compensation is obtained from:
F x d r a g = F r + F w + F g + F t ,
The total feedforward longitudinal torque is expressed as:
T f f = ( F x f f + F x d r a g ) R .

4.2. Feedback of Speed Controller

Robust asymptotic tracking can be achieved by the sliding mode control, therefore, it is applied here. To simplify the longitudinal dynamic model, assuming that the lateral velocity is zero, then we can get:
m v ˙ x = F x F r F w F g F t .
Using the pure rolling assumption that ω i j = v x i j / R , the wheel dynamics in Equation (2) can be rewritten as:
I ω i v ˙ x i j R = T i j F x i j R i j = f l , f r , r l , r r .
Combining Equations (10) and (11):
( m + I ω i j R 2 ) v ˙ x = T R F r F w F g F t , i j = f l , f r , r l , r r ,
where T is total control input torque, and T = T f f + T f b , T f b is the feedback control input torque.
Define the tracking error v e = v x v d , v d is the desired speed. Then, the tracking problem can be turned into a stabilization problem. Considering the resistance estimation error term, the stabilization system can be expressed as follows by combining Equations (6)–(10):
( m + I ω i j R 2 ) v ˙ e = T f b + Δ ( ) , i j = f l , f r , r l , r r ,
where Δ ( ) is the bounded resistance estimation error, and it is considered that slew rate is small.
It is typical to choose the sliding surface as s = v e for a first order system, the sliding mode control law can be expressed as:
T f b = ( m + I ω i j R 2 ) k sgn ( s ) = k p sgn ( v e ) , i j = f l , f r , r l , r r ,
with sufficiently large control gain k p , ensures that s s ˙ p 0 | s | < 0 , for all s 0 . While ideal sliding mode control achieves zero steady-state error, it is well known that, in practices, sliding mode controllers suffer from chattering due to switch delays and un-modeled dynamics. To eliminate chattering, we use the saturation function s a t ( ) to replace the sign function sgn ( ) , but it can guarantee only ultimate boundness with respect to a compact set, which can be made arbitrarily small by decreasing the thickness ε of boundary layer. However, a too small value of ε will again induce chattering due to non-ideal effects:
T f b = k p s a t ( s ε ) ,
where s a t ( ) is defined as:
s a t ( y ) = { y , | y | 1 sgn ( y ) , | y | > 1   .
Zero steady-state error can be achieved by including integral action in the controller. This was done by Khalil [33] by augmenting the system with an integrator driven by the tracking error: σ ˙ = v e . The sliding surface is taken as:
s = k 0 σ + v e ,
where the positive constant k 0 is chosen such that the system dynamics on sliding surface is controlled by v ˙ e = k 0 v e .
In this paper, the linear integrator is replaced by a nonlinear conditional integrator to avoid integral divergence and improve the transient performance:
σ ˙ = k 0 σ + ε s a t ( s ε ) .
At the actuator level, the electric brake is used for slight braking case to improve response speed and control accuracy, and the hydraulic brake compensation is used for heavy braking case.

4.3. Stability Analysis

To analyze the stability performance of the sliding mode controller with the conditional integrator, it is carried out from two aspects of inside the boundary layer and outside the boundary layer.

4.3.1. Inside the Boundary Layer ( | s | = | k 0 σ + v e | < ε )

Substituting Equation (15) into Equation (13), we can have:
{ v ˙ e = 1 m + I ω i j R 2 ( k p ε v e k p k 0 ε σ + Δ ( ) ) , i j = f l , f r , r l , r r σ ˙ = v e .
The closed-loop system has a unique equilibrium point ( v ¯ e , σ ¯ ) at ( 0 , ε k p k 0 Δ ( v d ) ) .
Selecting a Lyapunov candidate function:
V = 1 2 s ˜ 2 + 1 2 σ ˜ 2 ,
where σ ˜ = σ σ ¯ , s ˜ = s s ¯ and s ¯ = v ¯ x e + k i σ ¯ = k i σ ¯ .
Differentiating the left and right sides of Equation (20), it can be expressed as:
V ˙ = s ˜ s ˜ ˙ + σ ˜ σ ˜ ˙ = s ˜ s ˙ + σ ˜ σ ˙ = s ˜ ( v ˙ e + k 0 σ ˙ ) + σ ˜ v e = s ˜ m + I ω i j R 2 ( k p v e + k 0 σ ε + Δ ( v x ) ) + s ˜ k 0 v e + σ ˜ v e ,   i j = f l , f r , r l , r r = s ˜ m + I ω i j R 2 ( k p s ˜ + s ¯ ε + Δ ( v x ) ) + s ˜ k 0 v e + σ ˜ v e ,   i j = f l , f r , r l , r r .
Substituting v e = s k 0 σ = s ˜ k 0 σ ˜ into Equation (16), then the derivative of the Lyapunov function candidate can be rewritten as follows:
V ˙ = ( k ε k 0 ) s ˜ 2 + s ˜ m + I ω i j R 2 ( k p s ¯ ε + Δ ( v x ) ) ( k 0 2 1 ) s ˜ σ ˜ k 0 σ ˜ 2 .
Define a function f ( x ) = Δ ( x ) m + I ω i j R 2 ,   i j = f l , f r , r l , r r , when the continuous Lipschitz continuity condition is satisfied, it can be obtained that:
| f ( v x ) f ( v d ) | L | v e | = L | s ˜ k 0 σ ˜ | L | s ˜ | + L k 0 | σ ˜ | ,
where L is the Lipschitz constant.
Combining Equation (23) and s ¯ = k 0 σ ¯ = ε k p Δ ( v d ) , Equation (21) can be expressed as:
V ˙ = ( k ε k 0 ) s ˜ 2 + s ˜ ( Δ ( v x ) Δ ( v d ) m + I ω i j R 2 ) ( k 0 2 1 ) s ˜ σ ˜ k 0 σ ˜ 2 ( k ε k 0 ) s ˜ 2 + | s ˜ | ( L | s ˜ | + L k 0 | σ ˜ | ) ( k 0 2 1 ) s ˜ σ ˜ k 0 σ ˜ 2 = ( k ε k 0 L ) s ˜ 2 + ( L k 0 + 1 k 0 2 ) | s ˜ | | σ ˜ | k 0 σ ˜ 2 = ( | σ ˜ | | s ˜ | ) ( k 0 L k 0 + 1 k 0 2 2 L k 0 + 1 k 0 2 2 k ε k 0 L ) ( | σ ˜ | | s ˜ | ) .
If the inequality k 0 > 0 and k 0 ( k ε k 0 L ) ( L k 0 + 1 k 0 2 2 ) 2 > 0 are both satisfied, V ˙ is negative definite. Therefore, the equilibrium point is globally asymptotically stable if the control parameters satisfy the following equation:
{ k 0 > 0 0 < ε < [ k 0 k + L k + 1 k k 0 ( L k 0 + 1 k 0 2 2 ) 2 ] 1 .

4.3.2. Outside the Boundary Layer ( | s | = | k 0 σ + v e | ε )

Substituting Equation (15) into Equation (13), the control law outside the boundary layer can be expressed as:
{ T f b = k p sgn ( s ) σ ˙ = k 0 σ + ε sgn ( s ) .
It can be seen that the feedback control input converges to k p sgn ( s ) , the value of σ ˙ converges to zero, and σ becomes ε sgn ( s ) . Thus, the controller can prevent integral action from divergence. Furthermore, when v ˙ d sgn ( s ) > 0 is satisfied, it reaches the set { | s | ε } in finite time and remains inside thereafter.

5. Lateral Path Following Controllers Design

To obtain a simple, reliable, and robust path following controller that can handle complex situations, three lateral control schemes are proposed and compared. First, a LPV-MPC lateral control-based strategy is designed due to its ability of preview and handles constraints. Second, considering the simple control structure and good robustness, the nonlinear ADRC is applied to develop the second lateral controller. The third controller is based on the pure pursuit method, which is provided as a benchmark.

5.1. LPV-MPC Controller

Despite nonlinear MPC is attractive because of its ability to capture the nonlinearity of vehicle dynamics, the model complexity limited real-time implementation. Here, a LPV-MPC control law is designed.

5.1.1. Vehicle Model Discretization and Augmentation

The continuous vehicle model Equation (5) is discretized at each time step with a zero-order hold approximation that assumes constant continuous inputs over the duration of each discrete time step. The resulting discretized vehicle model is:
x ( k + 1 ) = A k x ( k ) + B k u ( k ) + D k w ( k ) y ( k ) = C k x ( k ) ,
where A k = I n + A t T s , B k = B t T s , D k = D t T s , C k = C t , T s is the sampling time.
To eliminate the steady-state error, we change the control input u ( k ) to the rate of change of the input Δ u ( k ) = u ( k ) u ( k 1 ) that can achieve the steady-state performance like an integral action, and augment the state vector as ξ ( k ) = [ x ( k ) u ( k 1 ) w ( k 1 ) ] T . Thus, the augmented system model becomes:
ξ ( k + 1 ) = A ξ ( k ) + B Δ u ( k ) y ( k ) = C ξ ( k ) ,
in which:
A = [ A k B k D k 0 I 0 0 0 1 ] , B = [ B k I 0 ] , C = [ C k 0 0 ] .

5.1.2. MPC Problem Formulation

Assuming that the current moment is k , the signals ξ ( k + j | k ) , Δ u ( k + j | k ) , and y ( k + j | k ) represent the future value of the states, inputs, and outputs respectively. Considering the prediction based on the discrete state space model (28), the predict states can be obtained by iteration:
{ ξ ( k + 1 | k ) = A ξ ( k ) + B Δ u ( k | k ) ξ ( k + 2 | k ) = A ξ ( k + 1 | k ) + B Δ u ( k + 1 | k ) = A 2 ξ ( k ) + A B Δ u ( k | k ) + B Δ u ( k + 1 | k ) ξ ( k + N p | k ) = A N p ξ ( k ) + A N p 1 B Δ u ( k | k ) + A N p 2 B Δ u ( k + 1 | k ) + + A N p N c B Δ u ( k + N c 1 | k ) ,
where N p is the predict horizon, N c is the control horizon, and N c N p that means Δ u ( k + j | k ) = 0 when j N c . Then, the predicted outputs can be expressed as follows:
{ y ( k + 1 | k ) = C A ξ ( k ) + C B Δ u ( k | k ) y ( k + 2 | k ) = C A 2 ξ ( k ) + C A B Δ u ( k | k ) + C B Δ u ( k + 1 | k ) y ( k + 3 | k ) = C A 3 ξ ( k ) + C A 2 B Δ u ( k | k ) + C A B Δ u ( k + 1 | k ) + C B Δ u ( k + 2 | k ) y ( k + N p | k ) = C A N p ξ ( k ) + C A N p 1 B Δ u ( k | k ) + C A N p 2 B Δ u ( k + 1 | k ) + + C A N p N c B Δ u ( k + N c 1 | k ) .
To reduce the notational complexity, the predicted outputs can be expressed as:
Y ( k ) = Φ ξ ( k ) + Θ Δ U ( k ) ,
in which:
Y ( k ) = [ y ( k + 1 | k ) y ( k + 2 | k ) y ( k + N p | k ) ] , Δ U ( k ) = [ Δ u ( k | k ) Δ u ( k + 1 | k ) Δ u ( k + N c 1 | k ) ] Φ = [ C A C A 2 C A 3 C A N p ] , Θ = [ C B 0 0 0 C A B C B 0 0 C A 2 B C A B C B 0 C A N p 1 B C A N p 2 B C A N p 3 B C A N p N c B ] .
The objective of the lateral controller is to track the desired path accurately and smoothly. Therefore, define the cost function as:
J ( ξ ( k ) , Δ U k ) = i = 1 N p y ( k + i | k ) y r e f ( k + i | k ) Q 2   + i = 0 N c 1 Δ u ( k + i | k ) R 2 ,
where weight matrix Q is symmetric semi-positive definite, R is symmetric positive definite.
Substituting Equation (31) into Equation (32), the cost function can be rewritten as:
J ( ξ ( k ) , Δ U k ) = ( Y ( k ) Y r e f ( k ) ) T Q ( Y ( k ) Y r e f ( k ) ) + Δ U T ( k ) R Δ U ( k ) = ( E + Θ Δ U ( k ) ) T Q ( E + Θ Δ U ( k ) ) + Δ U T ( k ) R Δ U ( k ) = Δ U T ( k ) ( Θ T Q Θ + R ) Δ U ( k ) + 2 E T ( k ) Q Θ Δ U ( k ) + E T ( k ) Q E ( k ) ,
where E ( k ) = Φ ξ ( k ) , and E T ( k ) Q E ( k ) is constant, then the cost function is expressed as:
J ( ξ ( k ) , Δ U k ) = 1 2 Δ U T ( k ) H Δ U ( k ) + g T Δ U ( k ) ,
where hessian matrix H = 2 ( Θ T Q Θ + R ) , and gradient matrix g = 2 Θ T Q E ( k ) .
Considering the constraint u min u ( k ) u max on the steering angle, the control input sequence U ( k ) and control increment sequence Δ U ( k ) satisfy the equation:
U ( k ) = M Δ U ( k ) + Γ u ( k 1 ) ,
in which:
M = [ I 0 0 I I 0 0 I I I I ] , Γ = [ I I I ] , U ( k ) = [ u ( k | k ) u ( k + 1 | k ) u ( k + N c 1 | k ) ] .
Considering the constraint Δ u min Δ u ( k ) Δ u max on steering angle increment, we can have:
Δ U min Δ U ( k ) Δ U max .
Considering the outputs constraint y min y y max , the predicted output sequence satisfies:
Y min Φ ξ ( k ) + Θ Δ U ( k ) Y max .
Considering the states soft constraint of slip angle of front axle α f min ς α f α f max + ς , the constraint is stated as:
M Δ U ( k ) S ( k ) α min ( k ) + Γ u ( k 1 ) M Δ U ( k ) S ( k ) + α max ( k ) Γ u ( k 1 ) ,
in which:
S ( k ) = [ β + l f γ v x β + l f γ v x β + l f γ v x ] N c × 1 , α min ( k ) = [ α f min ς α f min ς α f min ς ] N c × 1 , α max ( k ) = [ α f max + ς α f max + ς α f max + ς ] N c × 1 .
Combining Equations (35)–(38), the constraints of control increment sequence Δ U ( k ) can be written as:
[ M M I I Θ Θ M M ] Δ U ( k ) [ U max Γ u ( k 1 ) U min + Γ u ( k 1 ) Δ U max Δ U min Y max Φ ξ ( k ) Y min + Φ ξ ( k ) S ( k ) α min ( k ) + Γ u ( k 1 ) S ( k ) + α max ( k ) Γ u ( k 1 ) ] ,
where U max , U min , Δ U max , Δ U min N c × 1 that consist of N c piece of u max , u min , Δ u max , Δ u min , respectively, similarly, Y max , Y min N p × 2 that consist of N p piece of y max , y min , respectively.
The final optimization problem takes the form:
min Δ U ( k )   ς J ( ξ ( k ) , Δ U k , ς ) = 1 2 [ Δ U T ( k ) ς ] H [ Δ U ( k ) ς ] + g T [ Δ U ( k ) ς ]     s . t .     Equation ( 39 ) ,
where the hessian matrix augmented as H = [ 2 ( Θ T Q Θ + R ) 0 0 ρ ] , the gradient matrix augmented as g = [ 2 Θ T Q E ( k ) 0 ] , ς is the slack variable, and ρ is the weight of slack variable.

5.1.3. Quadratic Program Solver

For the quadratic program representable problem as shown in Equation (40), CVXGEN provides a custom, high-speed solver that is library-free C code, which make an online solution as fast as possible. The optimization resolves each time step, as is standard with MPC, and the first element Δ u * ( k | k ) of optimal solution is applied to the system, and the feedback control law at time k is finally obtained:
u ( k | k ) = u ( k 1 ) + Δ u * ( k | k ) .

5.2. ADRC Controller

Since active disturbance rejection control has strong robustness to system uncertainties and external disturbances, and can be implemented easily, so the nonlinear ADRC is applied to design the lateral controller in this paper. The ADRC is evolved from proportional-integral-derivative (PID) and it inherits the core idea of PID that makes it such a success: the error driven, rather than model-based [15].

5.2.1. ADRC Theoretical Basis

As shown in Figure 3, the nonlinear ADRC consists of three components: the tracking differentiator (TD), extended state observer (ESO), and nonlinear feedback combination (NFC). The TD provides the fastest tracking of the input signal and its derivative, and also arranges the transition process; the ESO considers the total disturbance as a new state variable and gives its estimation; the nonlinear feedback provides surprisingly better results than linear feedback, which play an important role in the ADRC framework.
Consider a single input and single output nonlinear n-order dynamic system:
{ x ( n ) = f ( x , x ˙ , , x ( n 1 ) , w , t ) + b u y = x ,
where y is the output, u is the input, w is the external disturbance, and f ( x , x ˙ , , x ( n 1 ) , w , t ) is a multivariable function of both the states and external disturbances, as well as time. The objective here is to make y track reference signal v 0 ( t ) using u as the manipulative variable.
To provide the fastest tracking of v 0 ( t ) and get its derivatives, the TD in discrete-time implementation is written as:
{ v 1 ( k + 1 ) = v 1 ( k ) + h v 2 ( k + 1 ) v 2 ( k + 1 ) = v 2 ( k ) + h v 3 ( k + 1 ) v n ( k + 1 ) = v n ( k ) + h u u = f h a n ( v 1 , v 2 , , v n , r 0 , h 0 ) ,
where h is the sampling period, f h a n ( ) is the time-optimal solution function, r 0 and h 0 are controller parameters.
f ( x , x ˙ , , x ( n 1 ) , w , t ) is denoted as the total disturbance which is something needed to overcome in the context of feedback control. Introducing an additional state variable x n + 1 = f ( x , x ˙ , , x ( n 1 ) , w , t ) , and let x ˙ n + 1 = d ( t ) , with d ( t ) unknown. The dynamic system is now described as:
{ x ˙ 1 = x 2 x ˙ 2 = x 3 x ˙ n = x n + 1 + b u x ˙ n + 1 = d ( t ) y = x 1 ,
where is always observable. Then, we can construct an extended state observer in the form of:
{ e = z 1 y z ˙ 1 = z 2 β 1 g 1 ( e ) z ˙ 2 = z 3 β 2 g 2 ( e ) z ˙ n = z n + 1 β n g n ( e ) + b u z ˙ n + 1 = β n + 1 g n + 1 ( e ) ,
where β i ( i = 1 , 2 , , n + 1 ) are the observer gains and g i ( e ) ( i = 1 , 2 , , n + 1 ) are nonlinear function of observation error e .
Finally, the control law using nonlinear feedback combination is proposed as:
u 0 = k 1 f a l ( e 1 , α 1 , δ ) + k 2 f a l ( e 2 , α 2 , δ ) + + k n f a l ( e n , α n , δ ) z n + 1 b ,
where k i ( i = 1 , 2 , , n ) are controller gains, e i ( i = 1 , 2 , , n ) are the tracking error of state variable, defined as e i = v i z i , f a l ( ) is a nonlinear function that defined as follows:
fal ( e , α , δ ) = { | e | α sign ( e ) ,   | e | > δ e / δ 1 α , | e | δ .
It should be pointed out that the controller coefficients are not dependent on the mathematical model of the plant, thus making ADRC largely model independent.

5.2.2. Application of ADRC

For the ADRC method, it is not suitable to process the single input multiple output coupling problem. Therefore, we only consider the lateral error stabilization in the ADRC scheme design. According to the lateral vehicle dynamics Equation (5), we can have:
y ¨ e = f ( y e , y ˙ e , w , t ) + ( 2 C α f m + 2 C α f l f l p I z ) δ f ,
where:
f ( y e , y ˙ e , w , t ) = v x 2 κ v x γ v x [ 2 ( C α f + C α r ) m v x β + ( 2 ( C α f l f C α r l r ) m v x 2 1 ) γ ] l p [ 2 ( C α f l f C α r l r ) I z β + 2 ( C α f l f 2 + C α r l r 2 ) I z v x γ ] .
Rewrite the equation as the state space form:
{ x ˙ 1 = x 2 x ˙ 2 = x 3 + b u x ˙ 3 = d ( t ) y = x 1 ,
where x 1 = y e , x 2 = y ˙ e , x 3 = f ( x 1 , x 2 , w , t ) , b = 2 C α f m + 2 C α f l f l p I z , u = δ f .
The ESO for lateral controller is designed as:
{ e = z 1 y z ˙ 1 = z 2 β 1 g 1 ( e ) z ˙ 2 = z 3 β 2 g 2 ( e ) + b u z ˙ 3 = β 3 g 3 ( e ) .
The control law using nonlinear feedback combination can be expressed as:
δ f = k 1 f a l ( e 1 , α 1 , δ ) + k 2 f a l ( e 2 , α 2 , δ ) + k 3 f a l ( e 3 , α 3 , δ ) z 3 b .

5.3. Pure Pursuit Controller

The pure pursuit method (PPM) is used as benchmark, shown in Figure 4. Its basic principle is to make the central control point of the rear axle reach the target point ( g x , g y ) along an arc by controlling the steering radius of an autonomous vehicle.
Based on the simple geometric bicycle model of an Ackerman steered vehicle, the pure pursuit control law is given as:
δ f = arctan ( 2 l sin ( α ) l d ) ,
where α is the angle between the vehicle heading vector and the look-ahead vector, l is the wheel base, and l d is the look-ahead distance.

6. Results and Discussion

In order to evaluate and compare the performance of the proposed path following controllers, a series of simulation experiments have been conducted. The main parameters of the autonomous vehicle are given as Table 1 which are taken from an actual prototype vehicle.

6.1. Case A: Speed Tracking

To validate the effectiveness of the proposed longitudinal speed tracking controller, stair step and sinusoidal tests have been carried out respectively, and simulation results are shown in Figure 5 and Figure 6. In the stair step case, we compared the improved sliding mode control with the basic sliding mode control to verify the performance improvement. As shown in Figure 5b, the speed error of basic sliding mode control has an obvious chattering effect near zero, which would cause a drastic change in the control input due to the discontinuous sign function. The improved sliding mode control shows a smooth action. It can be seen that the steady state error is almost zero and the overshoot is small. Meanwhile, the mean rise time is about 1.327 s. In the sinusoidal condition, the transient performance of the improved sliding mode speed controller is good. Therefore, the proposed speed tracking controller can provide an excellent performance for longitudinal speed control during the process of path following.

6.2. Case B: Skid Pad Test

To illustrate the steady state characteristics of the proposed lateral controllers for autonomous vehicles, the skid pad test was chosen. As shown as Figure 7a, it consists of two circular paths that intersect at a tangent point. Meanwhile, it includes a point with discontinuous curvature where vehicles transition from one circle to another, which can provide insight into robustness to path curvature.
Figure 7 demonstrates the responses of the designed lateral controllers. It can be seen that the steady state lateral error of the nonlinear ADRC controller is nearly zero and the steady state lateral error of LPV-MPC is about 0.0254 m, while the pure pursuit method-based controller suffers from higher steady state error. Besides, both the nonlinear ADRC and PPM controllers suffer from higher overshoot, in this case due to discontinuous curvature at the tangent point.

6.3. Case C: Double Lane Change Test

To investigate the transient response capability of the autonomous vehicle under the conditions of variable and large curvature, the double lane change path is designed, referring to the ISO 3888-2:2002 obstacle avoidance case, as shown in Figure 8.

6.3.1. Constant 5 m/s with the Given Path

In this case, the autonomous vehicle was set to pass through the test area at a constant longitudinal speed of 5 m/s, and the corresponding maximum lateral acceleration is about 1.2 m/s2.
The control results of the proposed lateral controllers are shown in Figure 9, based on which the control accuracy is then compared. The nonlinear ADRC and PPM controllers achieve almost the similar tracking accuracy in lateral error, while the LPV-MPC had an excellent performance that the maximum lateral error is 0.0061 m. The heading error of the LPV-MPC controller is the smallest, followed by the nonlinear ADRC and PPM controllers. As shown in Figure 9d, using the CVXGEN solver and computer with Intel i7-4770 CPU, the mean computation time of LPV-MPC is about 0.0012 s when predicting 20 steps that the sampling time is 0.02 s, while the others are more computationally efficient than the LPV-MPC controller.

6.3.2. Constant 10 m/s with the Given Path

The desired longitudinal speed is set to 10 m/s in this case, and the corresponding maximum lateral acceleration is about 4 m/s2 so that the tires are still in the linear zone.
The responses are presented in Figure 10. Similar to the case of 5 m/s, the LPV-MPC controller has the best transient performance, but the lateral error increases as the vehicle speed increases that the PPM controller has the same feature. It should be noted here that the lateral error of the nonlinear ADRC controller does not change significantly when the vehicle speed increases. This shows the robustness of the nonlinear ADRC controller to the uncertainties of model parameters.

6.3.3. Constant 15 m/s with the Given Path

The desired longitudinal speed is set to 15 m/s in this case, and the corresponding maximum lateral acceleration is about 8 m/s2 so that the tires show highly nonlinear characteristic.
The simulation results are shown in Figure 11. In this case, the performance of the PPM controller deteriorates significantly, with a maximum lateral error of 0.7258 m and obvious oscillation as well. The nonlinear ADRC controller still keeps stable to the vehicle speed even though large lateral acceleration, which is further verified that the nonlinear ADRC has strong robustness to parametric uncertainties. However, the transient performance of the LPV-MPC controller is worse than the nonlinear ADRC because the proposed LPV-MPC controller adopted a linear model and the actual vehicle dynamics is more nonlinear. The mean calculation time of the LPV-MPC controller is basically the same in these three double lane change tests.

6.4. Comprehensive Evaluation

As shown in Table 2, the maximum and root mean square values of lateral displacement error and heading angle error in the double lane change scenario are given, which provides a perspective of comparative analysis for the proposed path following schemes. When the constant test speed is no more than 10 m/s, the MPC has satisfactory control performance that the maximum lateral errors are 0.0061 m and 0.0372 m in test 1 and 4 respectively, far less than the nonlinear ADRC and PPM methods. However, the nonlinear ADRC shows the best performance in path following and the lateral error of MPC increases significantly due to the strong nonlinearity of tires in 15 m/s double lane change tests, while the PPM approach is not applicable because it only considers geometry but ignores vehicle dynamics. From the aspect of tracking performance, the nonlinear ADRC has strong robustness to speed variation. The heading angle error of each method and test is similar except for the PPM method at 15 m/s. The root mean square error indicates the transient performance during the tracking process, and the statistics show that there is the same trend as the maximum value.
Table 3 summarizes the advantages and drawbacks of each control strategy, it can be seen that none of the proposed controller is perfect and all methods can work well in some applications. MPC shows great potential in the vehicle control application with the development of theory and computing power. Nonlinear ADRC can provide strong robustness to uncertainties. The PPM can be used in parking maneuver and low speed vehicles such as sweepers.
An intuitive evaluation chart is formed by scoring the KPI (Key Performance Indication) of the simulation results, as shown in Figure 12. The score is based on a 5-point scale, with higher scores indicating better performance in that area. Here, the key performance indications include four aspects: path tracking accuracy, robustness to parameters uncertainties, ability to deal with curvature discontinuity, and simplicity of practical application, which represent the four axis terms in Figure 12. It should be noted that scores are evaluated from a perspective of subjective and objective combination. As mentioned above, the LPV-MPC can achieve excellent lateral control precision at low lateral acceleration, and the control accuracy is acceptable even at high lateral acceleration. Due to the predictive ability of MPC, it can also handle the curvature discontinuity of the path. However, MPC is relatively complex to deploy to hardware and requires processing unit of higher computing power. Therefore, the LPV-MPC scores 5, 2, 5, 3 points in these four indicators, respectively. For the nonlinear ADRC, the lateral error and heading error are larger than MPC comprehensively, but it is more robust to the vehicle speed. Meanwhile, the control structure of ADRC is simple and it can be implemented in an embedded vehicle control unit, but the parameters need to be calibrated carefully. Path curvature discontinuity would cause a larger overshoot in the nonlinear ADRC controller. In general, the nonlinear ADRC scores 4, 5, 3, 4 points, respectively. The pure pursuit method only works well in the low speed case but it is the simplest in practical application. Then, the PPM scores 3, 2, 3, 5 points in these indexes, respectively.
For model predictive control, further research is needed to build a good model that tradeoff between high fidelity and simple enough, and robust and stochastic MPC may be the future direction.

7. Conclusions

In this paper, three control schemes have been designed, verified, and compared for the path following application of autonomous vehicles. A longitudinal speed tracking controller is proposed based on sliding mode control with nonlinear conditional integrator, and stability analysis is also given. Considering the ability of preview and handling multi-constraints, the first lateral controller is based on the linear parameter varying model predictive control, which shows excellent tracking accuracy in the simulation tests. Though it requires real-time computations to solve the optimization problem, using the CVXGEN can achieve high efficiency to solve the QP problem. Nonlinear active disturbance rejection control is applied in the second lateral controller since ADRC is robust against the parametric uncertainties of vehicles. However, the comprehensive tracking performance is slightly worse than the MPC that was shown in comparison. The lateral controller via the pure pursuit method is used for a benchmark, which performs well in low speed case. The effectiveness and ability of the proposed schemes are validated by simulations. It should be noted that the LPV-MPC controller is relatively sensitive to the parametric uncertainties and the vehicle dynamics is highly nonlinear in large acceleration cases, therefore, the robust nonlinear model predictive control is our future research direction.

Author Contributions

Conceptualization, X.Y., L.X. and B.L.; methodology, X.Y.; software, X.Y.; validation, X.Y., L.X. and B.L.; formal analysis, X.Y.; investigation, X.Y.; resources, X.Y. and D.Z.; data curation, X.Y. and D.Z.; writing—original draft preparation, X.Y.; writing—review and editing, X.Y.; visualization, X.Y.; supervision, L.X., G.Z. and B.L.; project administration, B.L. and G.Z.; funding acquisition, X.Y. and B.L. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the National Natural Science Foundation of China (Grant No. 52002284), the National Key Research and Development Program of China (Grant No. 2018YFB0105804) and the National Key Research and Development Program of China (Grant No. 2018YFB0104805).

Acknowledgments

The authors thank the assistance from other people of the School of Automotive Studies, Tongji University and the Clean Energy Automotive Engineering Center, Tongji University.

Conflicts of Interest

The authors declare no conflict of interest. The funders had no role in the design of the study; in the collection, analyses, or interpretation of data; in the writing of the manuscript, or in the decision to publish the results.

References

  1. 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]
  2. De Winter, A.; Baldi, S. Real-Life Implementation of a GPS-Based Path-Following System for an Autonomous Vehicle. Sensors 2018, 18, 3940. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  3. Ni, J.; Hu, J. Dynamics control of autonomous vehicle at driving limits and experiment on an autonomous formula racing car. Mech. Syst. Signal Process 2017, 90, 154–174. [Google Scholar] [CrossRef]
  4. Talvala, K.L.R.; Kritayakirana, K.; Gerdes, J.C. Pushing the limits: From lane keeping to autonomous racing. Annu. Rev. Control 2011, 35, 137–148. [Google Scholar] [CrossRef]
  5. Li, S.E.; Qin, X.; Li, K.; Wang, J.; Xie, B. Robustness Analysis and Controller Synthesis of Homogeneous Vehicular Platoons with Bounded Parameter Uncertainty. IEEE/ASME Trans. Mech. 2017, 22, 1014–1025. [Google Scholar] [CrossRef]
  6. Buehler, M.; Iagnemma, K.; Singh, S. The DARPA Urban Challenge; Springer: Berlin, Germany, 2009. [Google Scholar]
  7. Xu, L.; Wang, Y.; Sun, H.; Xin, J.; Zheng, N. Integrated Longitudinal and Lateral Control for Kuafu-II Autonomous Vehicle. IEEE Trans. Intell. Transp. Syst. 2016, 17, 2032–2041. [Google Scholar] [CrossRef]
  8. Self-Driving Cars from Tesla, Google, and Others Are Still Not Here-Vox. Available online: https://www.vox.com/future-perfect/2020/2/14/21063487/self-driving-cars-autonomous-vehicles-waymo-cruise-uber (accessed on 9 August 2020).
  9. Snider, J.M. Automatic Steering Methods for Autonomous Automobile Path Tracking; Carnegie Mellon University Pittsburgh PA Robotics Institute: Pittsburgh, PA, USA, 2009; CMURI-TR-09-08. [Google Scholar]
  10. Ackermann, J.; Guldner, J.; Sienel, W.; Steinhauser, R.; Utkin, V.I. Linear and nonlinear controller design for robust automatic steering. IEEE Trans. Control Syst. Technol. 1995, 3, 132–143. [Google Scholar] [CrossRef]
  11. Ji, X.; He, X.; Lv, C.; Liu, Y.; Wu, J. Adaptive-neural-network-based robust lateral motion control for autonomous vehicle at driving limits. Control Eng. Pract. 2018, 76, 41–53. [Google Scholar] [CrossRef]
  12. Guo, H.; Shen, C.; Zhang, H.; Chen, H.; Jia, R. Simultaneous Trajectory Planning and Tracking Using an MPC Method for Cyber-Physical Systems: A Case Study of Obstacle Avoidance for an Intelligent Vehicle. IEEE Trans. Ind. Inform. 2018, 14, 4273–4283. [Google Scholar] [CrossRef]
  13. Liu, J.; Jayakumar, P.; Stein, J.L.; Ersal, T. A nonlinear model predictive control formulation for obstacle avoidance in high-speed autonomous ground vehicles in unstructured environments. Veh. Syst. Dyn. 2018, 56, 853–882. [Google Scholar] [CrossRef]
  14. Gao, Y.; Gray, A.; Tseng, H.E.; Borrelli, F. A tube-based robust nonlinear predictive control approach to semiautonomous ground vehicles. Veh. Syst. Dyn. 2014, 52, 802–823. [Google Scholar] [CrossRef]
  15. Han, J. From PID to Active Disturbance Rejection Control. IEEE Trans. Ind. Electron. 2009, 56, 900–906. [Google Scholar] [CrossRef]
  16. Mattingley, J.; Boyd, S. CVXGEN: A code generator for embedded convex optimization. Optim. Eng. 2012, 13, 1–27. [Google Scholar] [CrossRef]
  17. Thrun, S.; Montemerlo, M.; Dahlkamp, H.; Stavens, D.; Aron, A.; Diebel, J.; Fong, P.; Gale, J.; Halpenny, M.; Hoffmann, G.; et al. Stanley: The robot that won the DARPA Grand Challenge. J. Field Robot 2006, 23, 661–692. [Google Scholar] [CrossRef]
  18. Xu, S.; Peng, H.; Song, Z.; Chen, K.; Tang, Y. Design and Test of Speed Tracking Control for the Self-Driving Lincoln MKZ Platform. IEEE Trans. Intell. Veh. 2020, 5, 324–334. [Google Scholar] [CrossRef]
  19. Gerdes, J.C.; Hedrick, J.K. Vehicle speed and spacing control via coordinated throttle and brake actuation. Control Eng. Pract. 1997, 5, 1607–1614. [Google Scholar] [CrossRef]
  20. Kim, H.; Kim, D.; Shu, I.; Yi, K. Time-Varying Parameter Adaptive Vehicle Speed Control. IEEE Trans. Veh. Technol. 2016, 65, 581–588. [Google Scholar] [CrossRef]
  21. Zhu, M.; Chen, H.; Xiong, G. A model predictive speed tracking control approach for autonomous ground vehicles. Mech. Syst. Signal Process 2017, 87, 138–152. [Google Scholar] [CrossRef]
  22. 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]
  23. Xu, S.; Peng, H. Design, Analysis, and Experiments of Preview Path Tracking Control for Autonomous Vehicles. IEEE Trans. Intell. Transp. Syst. 2020, 21, 48–58. [Google Scholar] [CrossRef]
  24. Tagne, G.; Talj, R.; Charara, A. Design and Comparison of Robust Nonlinear Controllers for the Lateral Dynamics of Intelligent Vehicles. IEEE Trans. Intell. Transp. Syst. 2016, 17, 796–809. [Google Scholar] [CrossRef]
  25. Falcone, P.; Borrelli, F.; Asgari, J.; Tseng, H.E.; Hrovat, D. Predictive Active Steering Control for Autonomous Vehicle Systems. IEEE Trans. Control Syst. Technol. 2007, 15, 566–580. [Google Scholar] [CrossRef]
  26. Falcone, P.; Tseng, H.E.; Borrelli, F.; Asgari, J.; Hrovat, D. MPC-based yaw and lateral stabilization via active front steering and braking. Veh. Syst. Dyn. 2008, 46 (Suppl. 1), 611–628. [Google Scholar] [CrossRef]
  27. Brown, M.; Funke, J.; Erlien, S.; Gerdes, J.C. Safe driving envelopes for path tracking in autonomous vehicles. Control Eng. Pract. 2017, 61, 307–316. [Google Scholar] [CrossRef]
  28. 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. 2017, 25, 1204–1216. [Google Scholar] [CrossRef]
  29. Brown, M.; Gerdes, J.C. Coordinating Tire Forces to Avoid Obstacles Using Nonlinear Model Predictive Control. IEEE Trans. Intell. Veh. 2020, 5, 21–31. [Google Scholar] [CrossRef]
  30. Liu, J.; Jayakumar, P.; Stein, J.L.; Ersal, T. A study on model fidelity for model predictive control-based obstacle avoidance in high-speed autonomous ground vehicles. Veh. Syst. Dyn. 2016, 54, 1629–1650. [Google Scholar] [CrossRef]
  31. Hu, C.; Jing, H.; Wang, R.; Yan, F.; Chadli, M. Robust H∞ output-feedback control for path following of autonomous ground vehicles. Mech. Syst. Signal Process 2016, 70–71, 414–427. [Google Scholar] [CrossRef]
  32. Chu, Z.; Sun, Y.; Wu, C.; Sepehri, N. Active disturbance rejection control applied to automated steering for lane keeping in autonomous vehicles. Control Eng. Pract. 2018, 74, 13–21. [Google Scholar] [CrossRef]
  33. Khalil, H. Nonlinear System, 3rd ed.; Springer: Berlin/Heidelberg, Germany, 2017. [Google Scholar]
Figure 1. Schematic of path following system. OXY is the global coordinate system and oxy is the vehicle body-fixed local coordinate system.
Figure 1. Schematic of path following system. OXY is the global coordinate system and oxy is the vehicle body-fixed local coordinate system.
Sensors 20 06052 g001
Figure 2. Block diagram of longitudinal speed controller via the sliding mode control with nonlinear conditional integrator.
Figure 2. Block diagram of longitudinal speed controller via the sliding mode control with nonlinear conditional integrator.
Sensors 20 06052 g002
Figure 3. Control block diagram of the nonlinear ADRC.
Figure 3. Control block diagram of the nonlinear ADRC.
Sensors 20 06052 g003
Figure 4. Diagram of the pure pursuit method.
Figure 4. Diagram of the pure pursuit method.
Sensors 20 06052 g004
Figure 5. System responses to stair step reference speed on the straight road: (a) Speed tracking results; (b) Speed tracking error.
Figure 5. System responses to stair step reference speed on the straight road: (a) Speed tracking results; (b) Speed tracking error.
Sensors 20 06052 g005
Figure 6. System responses to sinusoidal reference speed on the straight road: (a) Speed tracking results; (b) The resulting speed tracking error.
Figure 6. System responses to sinusoidal reference speed on the straight road: (a) Speed tracking results; (b) The resulting speed tracking error.
Sensors 20 06052 g006
Figure 7. Simulation results of the skid pad test with constant speed 10 m/s: (a) The spatial path of the vehicle following the given path; (b) Curvature of the given path; (c) The resulting lateral error; (d) The resulting heading angle error.
Figure 7. Simulation results of the skid pad test with constant speed 10 m/s: (a) The spatial path of the vehicle following the given path; (b) Curvature of the given path; (c) The resulting lateral error; (d) The resulting heading angle error.
Sensors 20 06052 g007
Figure 8. Setting of the double lane change test case: (a) Path; (b) Curvature.
Figure 8. Setting of the double lane change test case: (a) Path; (b) Curvature.
Sensors 20 06052 g008
Figure 9. Simulation results of double lane change with constant speed 5 m/s: (a) The spatial path of the vehicle following the given path; (b) The resulting lateral error; (c) The resulting heading angle error; (d) The computational time of the proposed LPV-MPC controller.
Figure 9. Simulation results of double lane change with constant speed 5 m/s: (a) The spatial path of the vehicle following the given path; (b) The resulting lateral error; (c) The resulting heading angle error; (d) The computational time of the proposed LPV-MPC controller.
Sensors 20 06052 g009
Figure 10. Simulation results of double lane change with constant speed 10 m/s: (a) The spatial path of the vehicle following the given path; (b) The resulting lateral error; (c) The resulting heading angle error; (d) The computational time of the proposed LPV-MPC controller.
Figure 10. Simulation results of double lane change with constant speed 10 m/s: (a) The spatial path of the vehicle following the given path; (b) The resulting lateral error; (c) The resulting heading angle error; (d) The computational time of the proposed LPV-MPC controller.
Sensors 20 06052 g010
Figure 11. Simulation results of double lane change with constant speed 15 m/s: (a) The spatial path of the vehicle following the given path; (b) The resulting lateral error; (c) The resulting heading angle error; (d) The computational time of the proposed LPV-MPC controller.
Figure 11. Simulation results of double lane change with constant speed 15 m/s: (a) The spatial path of the vehicle following the given path; (b) The resulting lateral error; (c) The resulting heading angle error; (d) The computational time of the proposed LPV-MPC controller.
Sensors 20 06052 g011aSensors 20 06052 g011b
Figure 12. Radar schematic of KPI score of the proposed lateral controllers.
Figure 12. Radar schematic of KPI score of the proposed lateral controllers.
Sensors 20 06052 g012
Table 1. Main parameters of the autonomous vehicle.
Table 1. Main parameters of the autonomous vehicle.
DefinitionSymbolValueUnit
Vehicle mass m 1381kg
Distance from COG to the front axle l f 1.117m
Distance from COG to the rear axle l r 1.188m
Yaw moment of inertia of the vehicle I z 1833.8kg/m2
Cornering stiffness of the front wheel C α f 30,087N/rad
Cornering stiffness of the rear wheel C α r 31,888N/rad
Spin inertia of the wheel I ω 0.4kg
Rolling radius of the wheel R 0.291m
Table 2. Quantitative statistics of lateral error and heading error in the double lane change scenario.
Table 2. Quantitative statistics of lateral error and heading error in the double lane change scenario.
Test No.Desired
Speed
Controller
Design
Maximum Lateral Error RMSE 1 of Lateral Error Maximum Heading Error RMSE of Heading Error
15 m/sMPC0.00610.00240.07760.0302
25 m/sADRC0.11270.05200.09410.0355
35 m/sPPM0.11070.04030.09660.0345
410 m/sMPC0.03720.01640.07350.0275
510 m/sADRC0.08720.04300.08330.0305
610 m/sPPM0.21860.09210.10800.0398
715 m/sMPC0.13120.05040.08060.0293
815 m/sADRC0.10330.04560.07960.0272
915 m/sPPM0.72580.32180.17930.0819
1 Root mean square error.
Table 3. Comparison of the lateral control strategies.
Table 3. Comparison of the lateral control strategies.
Controller DesignAdvantagesDrawbacks
LPV-MPC
  • Can exploit available preview
  • Easy to handles constraints
  • Excellent control accuracy
  • Requires real-time computations
  • Need a more accurate model
  • Rely on sideslip angle information
  • Sensitive to parametric uncertainties
ADRC
  • Robust against parameters uncertainties
  • Easy to implement
  • Controller gains are need to be tuned well to get higher precision of tracking
PPM
  • Simply enough
  • Performs well when driving slowly or parking
  • Neglect the vehicle dynamics, so it does not suitable to large lateral acceleration case
  • Suffer from overshoot and steady state error as speed increases
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Yang, X.; Xiong, L.; Leng, B.; Zeng, D.; Zhuo, G. Design, Validation and Comparison of Path Following Controllers for Autonomous Vehicles. Sensors 2020, 20, 6052. https://doi.org/10.3390/s20216052

AMA Style

Yang X, Xiong L, Leng B, Zeng D, Zhuo G. Design, Validation and Comparison of Path Following Controllers for Autonomous Vehicles. Sensors. 2020; 20(21):6052. https://doi.org/10.3390/s20216052

Chicago/Turabian Style

Yang, Xing, Lu Xiong, Bo Leng, Dequan Zeng, and Guirong Zhuo. 2020. "Design, Validation and Comparison of Path Following Controllers for Autonomous Vehicles" Sensors 20, no. 21: 6052. https://doi.org/10.3390/s20216052

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