Next Article in Journal
RGB-D-Based Framework to Acquire, Visualize and Measure the Human Body for Dietetic Treatments
Previous Article in Journal
Graphene-Based Biosensor for Early Detection of Iron Deficiency
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Two-Layer Controller for Lateral Path Tracking Control of Autonomous Vehicles

1
School of Automotive Engineering, Wuhan University of Technology, Wuhan 430070, China
2
Hubei Key Laboratory of Advanced Technology for Automotive Components, Wuhan University of Technology, Wuhan 430070, China
*
Author to whom correspondence should be addressed.
Sensors 2020, 20(13), 3689; https://doi.org/10.3390/s20133689
Submission received: 26 May 2020 / Revised: 27 June 2020 / Accepted: 29 June 2020 / Published: 1 July 2020
(This article belongs to the Section Intelligent Sensors)

Abstract

:
This paper presents a two-layer controller for accurate and robust lateral path tracking control of highly automated vehicles. The upper-layer controller, which produces the front wheel steering angle, is implemented with a Linear Time-Varying MPC (LTV-MPC) whose prediction and control horizon are both optimized offline with particle swarm optimization (PSO) under varying working conditions. A constraint on the slip angle is imposed to prevent lateral forces from saturation to guarantee vehicle stability. The lower layer is a radial basis function neural network proportion-integral-derivative (RBFNN-PID) controller that generates electric current control signals executable by the steering motor to rapidly track the target steering angle. The nonlinear characteristics of the steering system are modeled and are identified on-line with the RBFNN so that the PID controller’s control parameters can be adjusted adaptively. The results of CarSim-Matlab/Simulink joint simulations show that the proposed hierarchical controller achieves a good level of path tracking accuracy while maintaining vehicle stability throughout the path tracking process, and is robust to dynamic changes in vehicle velocities and road adhesion coefficients.

1. Introduction

Despite significant advances made in recent years, highly or fully automated driving of vehicles remains challenging in arbitrarily complex environments, due to numerous non-trivial issues to be addressed, among which is the path tracking control [1]. The aim of designing the path tracking controller is to ensure that the vehicle follows reference paths accurately and robustly in a timely manner under varying environmental and vehicular conditions on the premise of guaranteed vehicle stability [2]. In this study, we focus on the lateral control of autonomous vehicles.
Previously proposed path tracking schemes can be classified into 3 categories: (1) Geometric based control, including pure pursuit control [3,4], the Stanley Tracking Algorithm [5], etc., with which the front wheel angle is computed by investigating the geometric relationship among vehicle kinematics, reference paths and points of preview. Due to the neglect of vehicle dynamics in these strategies, both tracking accuracy and vehicle stability would be worsened as the vehicle speed increases. (2) Feedback control without prediction, including backstepping control [6], H control [7], sliding-mode control [8,9], adaptive control [10,11] and the combination of aforementioned algorithms [12]. In these strategies, explicit control laws are designed with regard to vehicle dynamics whose key characteristics are captured with mathematically complex models. Although it has been proven by both simulation studies and field tests that these control algorithms are effective in vehicle motion control, their performance under highly dynamic conditions are not satisfactory mainly due to the absence of prediction on future conditions and low tolerance on external disturbances [13]. (3) Model predictive control (MPC), which is well suited to optimization problems with multiple constraints and is characterized by prediction and optimization, is now increasingly adopted in implementing path tracking control of autonomous vehicles [14,15]. A path tracking controller built in the MPC framework employs a vehicle dynamics model to predict vehicle states and establishes a multivariate multi-objective function between the predicted states of the vehicle and the reference variables as an open-loop optimal problem. At each sampling time, a sequence of optimal steering angles is calculated by solving the control problem with multiple constraints, which is applied to the control process only during the following sampling interval. Then, a new optimal control sequence is calculated based on new measurements of the vehicle states over a shifted horizon. The benefit brought by rolling optimization on finite and shifting horizons is that MPC can optimize its control law throughout the process of control and therefore can cope with the dynamically changing characteristics of the controlled system. The linear time-varying (LTV) MPC is more applicable in practice as the basic control strategy due to its much higher computational efficiency as compared to nonlinear MPC (NMPC) [16].
Full capture of the nonlinearities of the vehicle in the prediction model is neither favorable nor possible when designing MPC controllers due to the enormously large computation overhead [17]. As a result, extensive efforts have been invested in proposing linearized models that can contribute to achieving a tradeoff between tracking accuracy and computation efficiency. Among these proposals, the proportional linearized tire model with the small-angle assumption is one that gets widely adopted in previously proposed MPC-based controllers [18,19,20]. However, it is not necessarily true to assume that the slip angle will stay small, especially when the vehicle speed is high and the road friction coefficient is low. Significant modeling error could be caused if the linearized tire model is used without imposing constraints on the slip angle as the lateral tire forces will be saturated and no longer increase linearly with the slip angle when the lateral vehicle dynamics enter the nonlinear zone. As a result, the predicted states of the vehicle would deviate from actual values and therefore affect control accuracy [21]. Although adopting a nonlinear tire model contributes to minimizing the modeling error, it is still important for the slip angle to be contained within a small interval. In the framework of LTV-MPC, the nonlinear prediction model is linearized at each control point of operation. As a result, even with a nonlinear tire model, significant modeling errors would still be caused when the control points of operation approach the nonlinear zone of tire dynamics. Therefore, a constraint on the slip angle is required.
To develop a path tracking controller that is robust to dynamic changes in working conditions and yet still benefits from the low computation burden with LTV-MPC, a nonlinear tire model with a constraint imposed on the slip angle is incorporated into the prediction model in this study.
To cope with arbitrarily complex driving conditions, a few proposals have also focused on dynamic control parameters including optimal sampling time [22,23] or adaptive weights of the cost function [15]. In [24], the authors point out the necessity of changing both the prediction horizon and control horizon as speed changes to maintain vehicle stability. Though, there is still limited research on fine-tuning the prediction horizon and control horizon other than setting these two parameters empirically or via trial-and-error [25,26]. This study proposes to optimize both parameters with regard to various vehicle speeds and road adhesion coefficients using the particle swarm optimization (PSO) algorithm.
Another major gap between previously proposed path tracking controllers and practical lateral control of autonomous vehicles is the absence of a precise model that depicts the nonlinear characteristics of the steering system. The consequences are two-fold.
First, the feedback of the actual steering angle is almost certainly distorted as the nonlinearities of the steering system are either completely neglected or overly simplified [27]. Some efforts have been made to approximate the steering system with linear representations. In [28], the steering system is identified with the prediction-error minimization (PEM) method, and a second-order system is established as the transfer function between the actual steering angle and the target. Han at al. [10] designed a second-order steering control model with the control auto-regression and moving-average (CARMA) method, and the parameters of the steering system are estimated with the method of forgetting factor recursive least squares (FFRLS). Though, the linear approximation of the rather complex nonlinear time-varying steering systems is deemed to be non-applicable for practical purposes. Besides, identifying system parameters under different steering conditions is quite tedious.
Second, as the steering angle is not a physical signal applicable to any type of steering actuators, it becomes impossible to verify the effectiveness of proposed controlling strategies via field tests.
Therefore, an efficient and robust control strategy developed based on an accurate steering system model, that outputs executable control signals such as electric current by actuators is an important step toward developing path tracking controllers for real-life autonomous driving. To identify the nonlinear characteristics of the controlled system online and adjust the control parameters adaptively, adaptive PID control strategies based on neural networks have been developed [10]. Li at al. [29] proposed a back propagation neural network (BPNN)-PID control strategy to eliminate the nonlinear friction in the electric power steering system. In our case, a RBFNN, which converges faster as compared to BPNN, is adopted.
This paper proposes a two-layer path tracking controller for lateral control of autonomous vehicles. The upper layer is a PSO-LTV-MPC controller built upon a 3-DOF vehicle dynamics model. With the root mean square (RMS) value of tracking deviation as the objective function, the combination of the prediction and the control horizon of the LTV-MPC algorithm under different working conditions in terms of vehicle velocities and road adhesion coefficients are optimized offline with PSO. To ensure vehicle stability while tracking reference paths, a slip angle constraint is introduced to prevent tire forces from saturation. The lower layer is a RBFNN-PID steering angle tracking controller that generates electric current control signals for the steering motor. The nonlinear characteristics of the steering system are identified on-line with the RBFNN, and the PID controller’s control parameters are adjusted adaptively. The proposed hierarchical controller is validated on the CarSim-Matlab/Simulink simulation platform under double lane-changing conditions with various velocities and road adhesion coefficients. The effectiveness of the proposed strategy is verified through extensive simulation tests.

2. Overview

Figure 1 shows the diagram of the lateral control system utilizing the multi-layer controller this study proposes. The reference path is presented as given information.
The upper-layer LTV-MPC controller, whose parameters are optimized offline with the PSO algorithm, generates the target steering angle of the front wheel. The lower-layer RBFNN-PID controller outputs the electric current required by the steer-by-wire (SBW) system for rapid tracking of the target steering angle.

3. Vehicle Dynamics Model

This study adopts the “bicycle model” which has been widely used to develop the prediction model of MPC [30], as shown in Figure 2. The definitions of the parameters are listed in Table 1.
With Newton’s Second Law applied, a vehicle dynamics model can be built as given in Equation (1):
{ m v ˙ y = m v x w + 2 ( F c f cos ( δ f ) + F l f sin ( δ f ) ) + 2 F c r φ ˙ = w I z w ˙ = 2 a ( F c f cos ( δ f ) + F l f sin ( δ f ) ) 2 b F c r Y ˙ = v x sin ( φ ) + v y cos ( φ )
where vy and vx represent the vehicle longitudinal speed, and lateral speed in the body-fixed coordinate system respectively. Y is the vehicle lateral position in the Cartesian coordinate system.
To compute the longitudinal forces and lateral forces of the front and rear wheels with tire dynamics coupling considered, a semi-empirical nonlinear model, the Pacejka tire model, is adopted. As given in Equation (2), the tire longitudinal and lateral forces are described as nonlinear functions of their respective parameters: the slip angle α and the longitudinal slip ratio κ with the effect of vertical load Fz, and the road friction coefficient μ. Figure 3 shows an example of the tire lateral forces versus longitudinal slip and slip angle, for the fixed values of μ.
{ F l f = f l f ( κ f , α f , μ , F z f ) F c f = f c f ( κ f , α f , μ , F z f ) F l r = f l r ( κ r , α r , μ , F z r ) F c r = f c r ( κ r , α r , μ , F z r )
We assume that the vehicle is equipped with an antilock brake system, and the tire longitudinal slip ratio κf and κr is therefore provided. As suggested in [22], if the slip angle is relatively small, it can be estimated with the vehicle longitudinal speed vy, the lateral speed vx, the Yaw rate w, and the front wheel steering angle δf, as given in Equations (3) and (4):
α f = v y + a w v x δ f
α r = v y b w v x
and the vertical load of the front and the rear wheels are defined as follows:
F z f = b m g 2 ( a + b ) ,   F z r = a m g 2 ( a + b )
The nonlinear vehicle dynamics model described in Equations (1)–(5) can be rewritten in a compact form as defined below:
ξ ˙ ( t ) = f μ ( t ) , κ ( t ) ( ξ ( t ) , δ f ( t ) )
where ξ is the state vector and ξ = [vy,w,φ,Y]T.
As we focus on the lateral control of the autonomous vehicle in this study, the longitudinal speed vx is set to be constant. For parameters in ξ, the yaw rate w, the heading angle φ, and the vehicle lateral position in Cartesian coordinate system Y can be measured with the yaw rate sensor and GPS/inertial measurement unit (IMU). Measuring the lateral velocity vy is more challenging both economically and technically. Instead, previous studies have proposed to estimate the vehicle sideslip angle, based on which vy can be calculated with vx being a known constant, utilizing vehicle dynamics models and observation techniques based on easily measurable parameters. Measurements from the differential GPS receiver and the IMU are fused with a Kalman filter to calculate the position, the orientation, and the longitudinal and lateral velocities of the vehicle [24,26]. For more adaptive and accurate estimation of the vehicle sideslip angle, measurable parameters such as the wheel angular velocity, yaw rate, and wheel angle are used [31,32,33,34]. Therefore, we draw the conclusion that all the parameters of vehicle states in ξ can be either directly measured or estimated from measurable parameters.

4. The PSO-LTV-MPC Controller

Both the prediction horizon and control horizon are optimized with PSO with regard to different speeds and road adhesion coefficients. In addition, a slip angle constraint, estimated based on the vehicle states and control variables, is imposed to avoid saturation of the lateral forces of tires and to ensure that the tires provide additional lateral forces when needed to resist the interference of external lateral forces.

4.1. Design of the LTV-MPC Controller

The objective of designing the LTV-MPC controller is to eliminate the deviations between the predicted vehicle outputs and their references with the optimal steering angles. We use the vehicle dynamics model described in Section 3 as the prediction model, to predict the vehicle outputs. A series of optimal steering angles are then calculated by solving the multi-objective multi-constraint QP problem to eliminate the deviations.
To obtain a finite-dimensional control problem, we discretize the nonlinear vehicle dynamics model in Equation (6) with a fixed sampling time Ts:
χ ( d + 1 ) = f ( χ ( d ) , Δ δ f ( d ) )
χ ( d ) = [ ξ ( d ) δ f ( d 1 ) ] T
where the control increment Δδf is chosen as the input, and Δδf (d) = δf (d) − δf (d−1).
The heading angle φ and the lateral position Y are chosen as the outputs λ. The new discrete LTV model is obtained by linearizing Equation (7) around an operating point with the method of state trajectory [24]:
χ ( d + 1 ) = M d χ ( d ) + N d Δ δ f ( d )
λ ( d ) = H c · χ ( d )
where
M d = [ A k B k 0 1 × 4 I ] ,   N d = [ B k I ] ,   H c = [ 0 0 1 0 0 0 0 0 1 0 ]
We define the current time as t and the measurable current vehicle states as χ(t). According to the control law of MPC, the control inputs remain unchanged between prediction horizon C and control horizon P. At each time step, the optimization problem of LTV MPC can be formed as follows:
min Δ δ f ( t ) i = 1 P Q [ λ t ( t + i ) λ t , r e f ( t + i ) ] 2 + i = 0 C 1 R [ Δ δ f , t ( t + i ) ] 2 s u b j .   t o   Eq . ( 12 13 )
χ t ( d + 1 ) = M d χ t ( d ) + N d Δ δ f , t ( d ) λ t ( d ) = H c · χ t ( d )
Δ δ f , t ( d ) = δ f , t ( d ) δ f , t ( d 1 )
δ f , min δ f , t ( d ) δ f , max Δ δ f , min Δ δ f , t ( d ) Δ δ f , max
where λref = [φref, Yref]T represents the reference signal. Q, R represents the weight matrix of controlled outputs and inputs respectively. The prediction model in Equations (13) and (14) is used to predict the vehicle’s behavior. The inequation in Equation (15) are the hard constraints of the control input and the control increment.
The above optimization problem is transformed into the following QP form:
min Δ U ( d ) X T H ˜ X + G X T s u b j .   t o [ I I R R ] X [ Δ δ f , max × o n e s ( C , 1 ) ( Δ δ f , min × o n e s ( C , 1 ) ) ( δ f , max δ f ( d 1 ) ) × o n e s ( C , 1 ) ( δ f , min + δ f ( d 1 ) ) × o n e s ( C , 1 ) ]
where
X = Δ U ( d ) H ˜ = 2 Ξ d T Q Ξ d + R E d = Γ d χ ( d ) Y r e f G = 2 E d T Q Ξ d Y r e f = [ λ r e f ( d + 1 ) λ r e f ( d + 2 ) λ r e f ( d + P ) ] Δ U ( d ) = [ Δ δ f ( d ) Δ δ f ( d + 1 ) Δ δ f ( d + C ) ] R = [ 1 0 0 1 1 0 1 1 1 ] C × C Γ d = [ H c M d H c M d M d + 1 H c i = 0 P 1 M d + i ] Ξ d = [ H c N d 0 0 H c M d N d H c N d 0 H c i = 1 P 1 M d + i N d H c i = 2 P 1 M d + i N d + 1 H c i = C P 1 M d + i N d + C 1 ]
By solving the QP problem presented in Equation (16) at time t, we get the control increment sequence ΔUt* = [Δδf,t*,…,Δδf,t+C* ]T. And the optimal control law is obtained:
δ f ( t ) = Δ δ f , t * + δ f ( t 1 )
where Δδf,t* is the first element of ΔUt*.
It should be noted that no constraint on the slip angle is so far imposed when solving the aforementioned objective function, thus the control sequence obtained is inapplicable under limited working conditions.
A discrete LTV prediction model of the tire slip angle is obtained by discretizing and linearizing the Equations (3) and (4):
α ( d ) = E α χ ( d ) + Z α Δ δ f ( d )
where
α = [ α f , α r ] T ,   Z α = [ 1 , 0 ] T , E α = [ 1 v x a v x 0 0 1 1 v x b v x 0 0 0 ]
Based on the measurable current vehicle states χ(t), the predictive outputs of tire slip angle over the prediction horizon are obtained:
α t ( d + 1 ) = E α χ t ( d + 1 ) + Z α Δ δ f , t ( d + 1 )  
We restraint the slip angle in the region as defined below
α min α t ( d + 1 ) α max
Then, the constraint of the slip angle is established as follows
[ Ω α Ω α ] X [ α max × o n e s ( C , 1 ) S α χ ( d ) S α χ ( d ) α min × o n e s ( C , 1 ) ]
where
S α = [ E α M d E α M d M d + 1 E α i = 0 P 1 M d + i ] Ω α = [ E α N d + Z α 0 0 E α M d N d + Z α E α B ˜ k + Z α 0 E α i = 1 P 1 M d + i N d + Z α α E α i = 2 P 1 M d + i N d + 1 + Z α E α i = C P 1 M d + i N d + C 1 + Z α ]
Lastly, by solving the QP problem in Equation (16) with the slip angle constraint in Equation (23), the control input increment is produced with the stability of the vehicle considered.

4.2. Optimizing Controller Parameters Using PSO Algorithm

To further improve the LTV-MPC controller’s performance, the PSO algorithm is adopted to find the optimal pairs of prediction horizon and control horizon with varying vehicle speed V and road friction coefficient μ.
As the average lateral error is chosen as the evaluation index of the path tracking performance, the fitness function of PSO is defined to be the RMS of the error in lateral positions, as expressed in Equation (25).
f = 1 N i = 1 N ( Y ( i ) Y r e f ( i ) ) 2
To achieve a tradeoff between the local and global searching ability of PSO, the inertia weight W of updating particle velocity is linearly decreased.
W ( f ) = W max ( W max W min ) f T max
where Tmax represents the maximum iteration number. The maximum and minimum inertia weight is set empirically to 0.9, 0.4 respectively.
As shown in Table 2, both prediction horizon and control horizon are optimized with PSO when the vehicle speed V = [10,15,20,25] m/s, and the friction coefficient of road μ = [0.3, 0.8]. The optimization process involves 4 steps:
Step 1:
Initialize particle positions and velocities. Set the population number Nf = 30, the maximum iteration number k = 30, learning factor C1 = C2 = 2, particle position information Pp = [P, C]. The upper boundary of the particle’s position is set to [30,30] while the lower boundary is set to [1,1]. The particle velocity Vp ϵ [–1,1]. The current iteration number T = 1;
Step 2:
Compute the particle’s fitness f, and choose the individual extremum PI, b and the group extremum PG, b;
Step 3:
Update Pp, Vp, and f based on PI,b and PG, b obtained in Step 2, and then update the PI,b and PG, b;
Step 4:
Check to see if the termination condition is satisfied. If not, back to step 2; else the procedure terminates.

5. The RBFNN-PID Front Wheel Angle Tracking Controller

With the aim to design a control strategy that is capable of handling the nonlinear time-varying (NTV) characteristics of the SBW system and outputs control signals that are executable by steering actuators, a RBFNN-PID controller is built as the lower-layer controller. First, a steering system model that depicts the electromechanical connection between the actual steering angle and its target is established. Then, the RBF neural network, which has fast learning convergence and strong nonlinear fitting ability, is implemented to identify the characteristics of the SBW system and tune the PID controller’s control parameters on-line.

5.1. Modeling the SBW System

The structural of the SBW model is shown in Figure 4, which is composed of an electric motor, a rack, a steering trapezium, and directive wheels. An SBW model that models the dynamics of the electric motor and steering actuators is built. We assume that the left steering angles of front wheels and the right one is identical. We derive the following equations:
The dynamics model of the electric motor is expressed as
{ J s θ ¨ s + B s θ ˙ s = T s T δ T δ = K s ( θ s x r g s r p ) T s = K i i
The rack dynamics model is expressed as
m r x ¨ r + B r x ˙ r + K r x r = K s ( θ s x r g s r p ) r p η p 2 ( K k p x r g s N l δ ) N l
The dynamics model of the directive wheel is expressed as
J f w δ ¨ + B k p δ ˙ = K k p ( x r N l δ ) T f
Definitions and values of variables presented in Equations (27)–(29) are shown in Table 3.
The steering resistant torque of the front wheel Tf is composed of the front wheel rolling resistant torque M1 and self-aligning torque M2, as expressed in Equation (30):
T f = M 1 + M 2 = f c b m g a + b + c b m g cos δ 180 ( a + b ) sin 2 β + b m v x 2 r ( a + b ) R sin γ cos δ
where c, β, and γ represent the offset distance of the front pin, the kingpin inclination, and the caster angle, respectively. R denotes the turning radius of the vehicle, and f denotes the rolling resistance coefficient.

5.2. The Steering Angle Tracking Controller Based on RBFNN-PID

Figure 5 illustrates the architecture of the proposed RBFNN-PID controller. The PID controller’s input is the deviation of the actual steering angle from its target, while the output is the current to be executed by the electric motor. Three parameters kP, kI, kD of the PID controller are tuned adaptively with the RBFNN [35,36].
The incremental PID controller is adopted and the control error is defined below:
d k = δ f , k δ k
The inputs of the controller are:
{ I 1 = d k d k 1 I 2 = d k I 3 = d k 2 d k 1 + d k 2
The incremental PID control low is expressed as follows:
{ i k = i k 1 + Δ i k Δ i k = ( K P 0 + Δ K P ) I 1 + ( K I 0 + Δ K I ) I 2 + ( K D 0 + Δ K D ) I 3
where ik represents the PID controller’s output at time k, and KP0, KI0, KD0 denote the corresponding initial values of KP, KI, KD respectively.
A RBFNN is implemented to identify the characteristics of the SBW system through analyzing the its sensitivity between the input signal and the output variable. Then, the control parameters of PID is tuned adaptively with gradient descent.
The index of tuning of the RBFNN is defined as follows:
E k = 1 2 d k 2
To minimize Ek, the incremental parameters of PID is tuned with gradient descent:
{ Δ K P = τ E K P = τ E δ δ Δ i Δ i K P = τ d ( t ) δ Δ i I 1 Δ K I = τ E K I = τ E δ δ Δ i Δ i K I = τ d ( t ) δ Δ i I 2 Δ K D = τ E K D = τ E δ δ Δ i Δ i K D = τ d ( t ) δ Δ i I 3
where τ represents the learning efficiency which falls in the interval [0,1], and ∂δ/Δi is the sensitivity of the controlled object, which is identified with the RBFNN.
The adopted RBFNN is a three-layer feedforward network, and its structure is shown in Figure 6. X denotes the input vector of the network which consists of the PID controller’s output incremental current Δik, the actual steering angle at the present time δk, and at the previous time δk−1.
The output of the RBFNN δm,k, is computed as follows:
δ m , k = j = 1 m w j h j
where wj represents the connection weight between hj and δm,k, and the transfer function hj is calculated as in Equation (36).
h j = exp [ X c j 2 2 b j 2 ]
where c = [cj1, cj2, …, cjn]T, b = [b1, b2, …, bm]T represent the center vector and the base width vector of the jth neuron, respectively.
Finally, the aforementioned sensitivity of the controlled object is identified as
δ k Δ i k δ m , k Δ i k = i = 1 m w i h i c i j x i b i 2

6. Simulation and Results

6.1. Simulation Design

The double lane change (DLC) trajectory proposed in [24] is used as the reference trajectory to and a series of simulation studies is conducted jointly with CarSim-Matlab/Simulink to verify the proposal of this study, A B-Class Hatchback model in CarSim is used and its parameters are shown in Table 4. The RMS value of the error in lateral positions is adopted to evaluate the 4 variants of controllers’ performance. Controller A is the pure-pursuit controller embedded in the CarSim driver model, controller B is the upper-level LTV-MPC controller presented in Section 4.1, controller C is the proposed two-layer tracking controller without the slip angle constraint, and controller D is the proposed two-layer tracking controller with the slip angle constraint.
Three test scenarios are implemented. Scenario 1 presents an emergency obstacle avoidance scene on a high adhesion road, in which the performance is compared among the controller A, B, and C. Scenario 2 presents an emergency obstacle avoidance scene on a low adhesion road, in which the performance is compared among the controller A, B, and C. Scenario 3 presents an emergency obstacle avoidance scene on a low adhesion road, in which the performance is compared between the controller C and D.

6.2. Analysis of Simulation Results

6.2.1. Scenario 1

On the road surface which friction coefficient is 0.8, three controllers are tested at different vehicle speeds ranging from 10 m/s to 25 m/s. Figure 6 show the tracking performance of 3 controllers. The lateral tracking deviations of 3 controllers are given in Table 5.
As shown in Figure 7, controller B and controller C both perform well at all speeds, while controller A can only achieve good tracking performance at relatively low speed (10 m/s). As the velocity increases, the lateral tracking deviations of controller B and controller C increase slowly, while the lateral tracking deviation of controller A increases significantly and gets much higher than another two MPC-based controllers. Besides, at the speed of 25 m/s, both controller B and controller C can still help to guarantee the vehicle’s lateral stability while tracking the reference path smoothly and accurately.
Moreover, the performances of controller B and controller C are quite close as shown in Table 5, which indicates that the lower-level RBFNN-PID controller proposed in Section 5 can effectively deal with the NTV characteristics of the SBW system and hence achieve no worse performance in path tracking as compared to the case of controller B where the steering system is completely neglected.

6.2.2. Scenario 2

To test the tracking performance of each controller on slippery roads, we set the road friction coefficient to 0.3 in this scenario. The lateral tracking deviations of 3 controllers are given in Table 6.
Due to the limited amount of frictional force available, the tracking error of all controllers in this scenario increases as the vehicle speed increases, as shown in Figure 8. However, it’s observed from simulation results that controller B and controller C still manage to track the path at high accuracy while maintaining the stability of the vehicle at medium and low speeds, and also achieve acceptable path tracking performance at high speeds.

6.2.3. Scenario 3

In this scenario, the tracking performance of controller C and controller D on a low friction coefficient road (μ = 0.3) is examined. The difference between the two controllers is that controller D is imposed with the slip angle constraint. Figure 9, Figure 10 and Figure 11 compare these two controllers in tracking performance. The lateral tracking deviations of both controllers are shown in Table 7.
As shown in Figure 10, when the vehicle speed is at or above 10 m/s, the front wheel steering angle of the vehicle with controller D is within a considerably smaller range as compared to the vehicle with controller C, indicating that the vehicle is more stable with controller D at high speeds. This is because the amount of frictional force available is greatly reduced and can be easily saturated with low friction coefficient conditions. The nonlinear tire model without the slip angle constraint lose the ability to predict the lateral tire force when the frictional tire forces saturates. With external lateral force applied at this time, the vehicle loses stability. On the contrary, the controller constrained by the slip angle ensures that the tires provide additional lateral forces when needed to resist the interference of external lateral forces such as lateral wind, thereby improving vehicle stability on low friction coefficient roads. Moreover, the results given in Table 7 and shown in Figure 9 suggest that the tracking performance of controller D matches with that of controller C when the vehicle speed is relatively low and outperforms when the vehicle speed is above 20 m/s. It confirms that imposing the slip angle constraint does not affect the tracking performance while guaranteeing the vehicle stability.
In conclusion, simulation results show that the proposed two-layer path tracking controller can track the reference paths accurately and smoothly while ensuring the vehicle’s stability, and is robust to dynamic changes in road surface conditions and vehicle speeds.

7. Conclusions

A hierarchical controller for lateral path tracking control of autonomous vehicles is proposed. The upper layer is a PSO-LTV-MPC controller considering the slip constraint which is estimated from measurable vehicle states, to avoid saturation of the lateral forces of tires. The prediction and the control horizon are both optimized offline with PSO, thereby improving the performance of the controller under dynamic conditions. The lower layer is a RBFNN-PID controller, which identifies the nonlinear characteristics of the steering system online and outputs an executable control signal for actuators, that is, the current of the steering executive motor, to achieve rapid tracking of the target steering angle produced by the upper controller. We verify the effectiveness of the proposed approaches with CarSim-Matlab/Simulink joint simulations under double lane changing conditions with the vehicle velocity and the road friction coefficient varies. The results show that as compared to the competitors, the proposed controller tracks the target path accurately while maintaining a good level of vehicle stability, and is robust to changes in road attachment conditions and vehicle speeds. Future research will attempt to further improve the tracking performance with coordinated lateral and longitudinal control.

Author Contributions

Conceptualization, Z.H. and Z.Y.; data curation, Z.H., L.N., and S.H.; formal analysis, Z.H., Z.Y., and L.N.; funding acquisition, Z.Y.; Investigation, Z.H. and L.N.; Methodology, Z.H., Z.Y., and L.N.; project administration, Z.Y.; resources, Z.H. and L.N.; software, Z.H. and L.N.; supervision, Z.Y.; validation, Z.H. and L.N.; visualization, Z.H., L.N., and S.H.; writing—original draft, Z.H., L.N., and S.H.; writing—review and editing, Z.H., Z.Y., L.N., and S.H. 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 number 51805388.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Zhang, C.; Hu, J.; Qiu, J.; Yang, W.; Sun, H.; Chen, Q. A Novel Fuzzy Observer-Based Steering Control Approach for Path Tracking in Autonomous Vehicles. IEEE Trans. Fuzzy. Syst. 2019, 27, 278–290. [Google Scholar] [CrossRef]
  2. Ren, B.; Chen, H.; Zhao, H.; Yuan, L. MPC-based yaw stability control in in-wheel-motored EV via active front steering and motor torque distribution. Mechatronics 2016, 38, 103–114. [Google Scholar] [CrossRef]
  3. Park, M.; Lee, S.; Han, W. Development of Steering Control System for Autonomous Vehicle Using Geometry-Based Path Tracking Algorithm. ETRI J. 2015, 37, 617–625. [Google Scholar] [CrossRef]
  4. Elbanhawi, M.; Simic, M.; Jazar, R. Receding horizon lateral vehicle control for pure pursuit path tracking. J. Vib. Control 2018, 24, 619–642. [Google Scholar] [CrossRef]
  5. Thrun, S.; Montemerlo, M.; Dahlkamp, H.; Stavens, D.; Aron, A.; Diebel, J.; Mahoney, P. Stanley: The robot that won the DARPA Grand Challenge. J. Field Robot 2006, 23, 661–692. [Google Scholar] [CrossRef]
  6. Kang, C.M.; Kim, W.; Chung, C.C. Observer-based backstepping control method using reduced lateral dynamics for autonomous lane-keeping system. ISA Trans. 2018, 83, 214–226. [Google Scholar] [CrossRef] [PubMed]
  7. Jing, H.; Wang, R.; Wang, J.; Chen, N. Robust H-infinity dynamic output-feedback control for four-wheel independently actuated electric ground vehicles through integrated AFS/DYC. J. Frankl. Inst. 2018, 355, 9321–9350. [Google Scholar] [CrossRef]
  8. Wang, Z.; Wang, Y.; Zhang, L.; Liu, M. Vehicle Stability Enhancement through Hierarchical Control for a Four-Wheel-Independently-Actuated Electric Vehicle. Energies 2017, 10, 9477. [Google Scholar] [CrossRef] [Green Version]
  9. Hu, C.; Wang, R.; Yan, F.; Huang, Y.; Wang, H.; Wei, C. Differential Steering Based Yaw Stabilization Using ISMC for Independently Actuated Electric Vehicles. IEEE Trans. Intell. Transp. Syst. 2018, 19, 627–638. [Google Scholar] [CrossRef]
  10. Han, G.; Fu, W.; Wang, W.; Wu, Z. The Lateral Tracking Control for the Intelligent Vehicle Based on Adaptive PID Neural Network. Sensors 2017, 17, 12446. [Google Scholar] [CrossRef] [Green Version]
  11. Guo, J.; Luo, Y.; Li, K. An Adaptive Hierarchical Trajectory Following Control Approach of Autonomous Four-Wheel Independent Drive Electric Vehicles. IEEE Trans. Intell. Transp. Syst. 2018, 19, 2482–2492. [Google Scholar] [CrossRef]
  12. Kim, W.; Kang, C.M.; Son, Y.S.; Chung, C.C. Nonlinear Backstepping Control Design for Coupled Nonlinear Systems under External Disturbances. Complexity 2019, 13, 7941302. [Google Scholar] [CrossRef]
  13. 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]
  14. Guo, J.; Luo, Y.; Li, K.; Dai, Y. Coordinated path-following and direct yaw-moment control of autonomous electric vehicles with sideslip angle estimation. Mech. Syst. Signal Process. 2018, 105, 183–199. [Google Scholar] [CrossRef]
  15. Wang, H.; Liu, B.; Ping, X.; An, Q. Path Tracking Control for Autonomous Vehicles Based on an Improved MPC. IEEE Access 2019, 7, 161064–161073. [Google Scholar] [CrossRef]
  16. Ataei, M.; Khajepour, A.; Jeon, S. Model Predictive Control for integrated lateral stability, traction/braking control, and rollover prevention of electric vehicles. Veh. Syst. Dyn. 2020, 58, 49–73. [Google Scholar] [CrossRef]
  17. Amer, N.H.; Zamzuri, H.; Hudha, K.; 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. 2017, 86, 225–254. [Google Scholar] [CrossRef]
  18. Ji, J.; Khajepour, A.; Melek, W.W.; Huang, Y. Path Planning and Tracking for Vehicle Collision Avoidance Based on Model Predictive Control with Multiconstraints. IEEE Trans. Veh. Technol. 2017, 66, 952–964. [Google Scholar] [CrossRef]
  19. Sun, C.; Zhang, X.; Xi, L.; Tian, Y. Design of a Path-Tracking Steering Controller for Autonomous Vehicles. Energies 2018, 11, 14516. [Google Scholar] [CrossRef] [Green Version]
  20. Wang, Z.; Li, G.; Jiang, H.; Chen, Q.; Zhang, H. Collision-Free Navigation of Autonomous Vehicles Using Convex Quadratic Programming-Based Model Predictive Control. IEEE-ASME Trans. Mech. 2018, 23, 1103–1113. [Google Scholar] [CrossRef]
  21. Ren, Y.; Zheng, L.; Khajepour, A. Integrated model predictive and torque vectoring control for path tracking of 4-wheel-driven autonomous vehicles. IET Intell. Transp. Syst. 2019, 13, 98–107. [Google Scholar] [CrossRef]
  22. Wei, S.; Zou, Y.; Zhang, X.; Zhang, T.; Li, X. An Integrated Longitudinal and Lateral Vehicle Following Control System with Radar and Vehicle-to-Vehicle Communication. IEEE Trans. Veh. Technol. 2019, 68, 1116–1127. [Google Scholar] [CrossRef]
  23. Guo, H.; Liu, J.; Cao, D.; Chen, H.; Yu, R.; Lv, C. Dual-envelop-oriented moving horizon path tracking control for fully automated vehicles. Mechatronics 2018, 50, 422–433. [Google Scholar] [CrossRef] [Green Version]
  24. Falcone, P.; Borrelli, F.; Asgari, J.; Tseng, H.E.; Hrovat, D. Predictive active steering control for autonomous vehicle systems. IEEE Trans. Contr. Syst. Technol. 2007, 15, 566–580. [Google Scholar] [CrossRef]
  25. Siampis, E.; Velenis, E.; Gariuolo, S.; Longo, S. A Real-Time Nonlinear Model Predictive Control Strategy for Stabilization of an Electric Vehicle at the Limits of Handling. IEEE Trans. Control Syst. Trans. 2018, 26, 1982–1994. [Google Scholar] [CrossRef]
  26. Guo, H.; Cao, D.; Chen, H.; Sun, Z.; Hu, Y. Model predictive path following control for autonomous cars considering a measurable disturbance: Implementation, testing, and verification. Mech. Syst. Signal Process. 2019, 118, 41–60. [Google Scholar] [CrossRef]
  27. Jiang, J.; Astolfi, A. Lateral Control of an Autonomous Vehicle. IEEE Trans. Intell. Veh. 2018, 3, 228–237. [Google Scholar] [CrossRef]
  28. Kim, E.; Kim, J.; Sunwoo, M. Model predictive control strategy for smooth path tracking of autonomous vehicles with steering actuator dynamics. Int. J. Automot. Technol. 2014, 15, 1155–1164. [Google Scholar] [CrossRef]
  29. Li, Y.; Wu, G.; Wu, L.; Chen, S. Electric power steering nonlinear problem based on proportional-integral-derivative parameter self-tuning of back propagation neural network. SAGE J. 2020, 0954406220926549. [Google Scholar] [CrossRef]
  30. Falcone, P.; Tseng, H.E.; Borrelli, F.; Asgari, J.; Hrovat, D. MPC-based yaw and lateral stabilisation via active front steering and braking. Veh. Syst. Dyn. 2008, 46, 611–628. [Google Scholar] [CrossRef]
  31. Grip, H.F.; Imsland, L.; Johansen, T.A.; Fossen, T.I.; Kalkkuhl, J.C.; Suissa, A. Nonlinear vehicle side-slip estimation with friction adaptation. Automatica 2008, 44, 611–622. [Google Scholar] [CrossRef]
  32. You, S.; Hahn, J.; Lee, H. New adaptive approaches to real-time estimation of vehicle sideslip angle. Control Eng. Pract. 2009, 17, 1367–1379. [Google Scholar] [CrossRef]
  33. Doumiati, M.; Victorino, A.C.; Charara, A.; Lechner, D. Onboard Real-Time Estimation of Vehicle Lateral Tire-Road Forces and Sideslip Angle. IEEE ASME Trans. Mech. 2011, 16, 601–614. [Google Scholar] [CrossRef]
  34. Li, L.; Jia, G.; Ran, X.; Song, J.; Wu, K. A variable structure extended Kalman filter for vehicle sideslip angle estimation on a low friction road. Veh. Syst. Dyn. 2014, 52, 280–308. [Google Scholar] [CrossRef]
  35. Nie, L.; Guan, J.; Lu, C.; Zheng, H.; Yin, Z. Longitudinal speed control of autonomous vehicle based on a self-adaptive PID of radial basis function neural network. IET Intell. Transp. Syst. 2018, 12, 485–494. [Google Scholar] [CrossRef]
  36. Du, Z.; Ye, Z.; Zhang, H.; Bai, H.; Xu, Y.; Jiang, X. In The Study of Trajectory Automatic Control Based on RBF Neural Network PID Control. In Proceedings of the 2015 International Conference on Fluid Power and Mechatronics (FPM), Harbin, China, 5–7 August 2015; pp. 1234–1238. [Google Scholar]
Figure 1. The diagram of the path tracking control system.
Figure 1. The diagram of the path tracking control system.
Sensors 20 03689 g001
Figure 2. Vehicle dynamics model.
Figure 2. Vehicle dynamics model.
Sensors 20 03689 g002
Figure 3. The tire lateral forces versus longitudinal slip and slip angle.
Figure 3. The tire lateral forces versus longitudinal slip and slip angle.
Sensors 20 03689 g003
Figure 4. SBW system model.
Figure 4. SBW system model.
Sensors 20 03689 g004
Figure 5. The architecture of the RBFNN-PID controller.
Figure 5. The architecture of the RBFNN-PID controller.
Sensors 20 03689 g005
Figure 6. The structure of RBFNN.
Figure 6. The structure of RBFNN.
Sensors 20 03689 g006
Figure 7. Tracking performance of 3 controllers in terms of the lateral position at different vehicle velocities. (a) 10 m/s; (b) 15 m/s; (c) 20 m/s; (d) 25 m/s.
Figure 7. Tracking performance of 3 controllers in terms of the lateral position at different vehicle velocities. (a) 10 m/s; (b) 15 m/s; (c) 20 m/s; (d) 25 m/s.
Sensors 20 03689 g007
Figure 8. Tracking performance of 3 controllers in terms of the lateral position at different vehicle velocities. (a) 10 m/s; (b) 15 m/s; (c) 20 m/s; (d) 25 m/s.
Figure 8. Tracking performance of 3 controllers in terms of the lateral position at different vehicle velocities. (a) 10 m/s; (b) 15 m/s; (c) 20 m/s; (d) 25 m/s.
Sensors 20 03689 g008
Figure 9. Tracking performance of 3 controllers in terms of the lateral position at different vehicle velocities. (a) 10 m/s; (b) 15 m/s; (c) 20 m/s; (d) 25 m/s.
Figure 9. Tracking performance of 3 controllers in terms of the lateral position at different vehicle velocities. (a) 10 m/s; (b) 15 m/s; (c) 20 m/s; (d) 25 m/s.
Sensors 20 03689 g009
Figure 10. The desired and controlled steering angle of the front wheel with the controller C and D at different vehicle velocities. (a) 10 m/s; (b) 15 m/s; (c) 20 m/s; (d) 25 m/s.
Figure 10. The desired and controlled steering angle of the front wheel with the controller C and D at different vehicle velocities. (a) 10 m/s; (b) 15 m/s; (c) 20 m/s; (d) 25 m/s.
Sensors 20 03689 g010aSensors 20 03689 g010b
Figure 11. Slip angle at different vehicle velocities. (a) 10 m/s; (b) 15 m/s; (c) 20 m/s; (d) 25 m/s.
Figure 11. Slip angle at different vehicle velocities. (a) 10 m/s; (b) 15 m/s; (c) 20 m/s; (d) 25 m/s.
Sensors 20 03689 g011
Table 1. Bicycle model parameters.
Table 1. Bicycle model parameters.
SymbolDescription
Flf/FcfLongitudinal force/lateral force of the front wheel
Flr/FcrLongitudinal force/lateral force of the rear wheel
a/bDistance of front/rear axle from the center of gravity
mVehicle Mass
rWheel radius
κf/κrThe tire longitudinal slip ratio of front/rear tires
Ccr/ClrLateral stiffness/longitudinal stiffness of rear tire
αfrSlip angle of front/rear tire
Ccf/ClfLateral stiffness/longitudinal stiffness of front tire
IzVehicle inertia
δfFront wheel steering angle
φHeading angle
wYaw rate
Table 2. Optimized pairs of prediction horizon and control horizon.
Table 2. Optimized pairs of prediction horizon and control horizon.
Vehicle Speed(m/s)The Friction Coefficient of RoadPrediction Horizon NPControl Horizon NC
100.387
0.888
150.3112
0.887
200.3236
0.899
250.3252
0.81010
Table 3. Parameters of the SBW model.
Table 3. Parameters of the SBW model.
SymbolDefinitionValue
JsMotor shaft inertia0.00019 kg m2
BsMotor shaft damping coefficient0.0034 N m/(rad/s)
KsMotor shaft torsional stiffness115 N m/rad
gsMotor speed reduction ratio10
mrRack mass2.57 kg
BrRack damping coefficient314 N/(m/s)
KrRack spring constant91085 N/m
rpPinion radius0.009 m
ŋpSteering gear transmission efficiency1
JfwSteering tire inertia0.82 kg m2
KiTorque coefficient of the motor0.0718 N m/A
NlTransmission ratio from rack to steering tire 0.1003
BkpSteering tire damping coefficient197 N m/(rad/s)
KkpSteering tire torsion stiffness39951.6 N m/rad
Table 4. Vehicle model parameters.
Table 4. Vehicle model parameters.
SymbolValue
m1843 kg
Iz4175 kg m2
a1.232 m
b1.468 m
r0.308 m
Table 5. Lateral deviations of 3 controllers at different vehicle velocities V(m/s).
Table 5. Lateral deviations of 3 controllers at different vehicle velocities V(m/s).
Controller Δ Y R M S   ( m )
V = 10V = 15V = 20V = 25
A0.06720.16080.28351.6067
B0.05460.09730.16430.2964
C0.05840.09850.16790.3022
Table 6. Lateral deviations of 3 controllers at different vehicle velocities V(m/s).
Table 6. Lateral deviations of 3 controllers at different vehicle velocities V(m/s).
Controller Δ Y R M S   ( m )
V = 10V = 15V = 20V = 25
A0.03200.87942.24122.6585
B0.06200.33480.47760.6731
C0.06220.33650.47640.6657
Table 7. Lateral deviations of 2 controllers at different vehicle velocities V(m/s).
Table 7. Lateral deviations of 2 controllers at different vehicle velocities V(m/s).
Controller Δ Y R M S   ( m )
V = 10V = 15V = 20V = 25
C0.06220.33650.47640.6657
D0.06630.36090.46160.6229

Share and Cite

MDPI and ACS Style

He, Z.; Nie, L.; Yin, Z.; Huang, S. A Two-Layer Controller for Lateral Path Tracking Control of Autonomous Vehicles. Sensors 2020, 20, 3689. https://doi.org/10.3390/s20133689

AMA Style

He Z, Nie L, Yin Z, Huang S. A Two-Layer Controller for Lateral Path Tracking Control of Autonomous Vehicles. Sensors. 2020; 20(13):3689. https://doi.org/10.3390/s20133689

Chicago/Turabian Style

He, Zhiwei, Linzhen Nie, Zhishuai Yin, and Song Huang. 2020. "A Two-Layer Controller for Lateral Path Tracking Control of Autonomous Vehicles" Sensors 20, no. 13: 3689. https://doi.org/10.3390/s20133689

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