Introduction

As a burgeoning trend in the future development of the automotive industry, the core intelligent features of autonomous driving technology are reflected in the field of intelligent and safe driving. Given the challenges posed by a concerning traffic safety situation, excessive energy consumption, and increased environmental pollution, intelligent vehicles, as an integral component of the intelligent transportation system, are garnering increasing attention and significanc1,2. The functional architecture of automated vehicles can be primarily divided into three major components: comprehensive perception, decision planning, and motion control. Among these, the motion control system is responsible for executing specific actuator commands based on the desired driving path derived from comprehensive sensing and decision planning, as well as real-time feedback on the vehicle’s status. This ensures that the vehicle can navigate smoothly along the intended trajectory. Trajectory tracking control serves as a crucial link between the planning layer and the execution layer, playing a vital role in determining the stability and safety of the vehicle system3. Its performance directly influences both the safety of the vehicle and the overall passenger experience. Therefore, conducting in-depth research on vehicle trajectory-tracking control systems is particularly important.

In recent years, numerous studies have focused on trajectory-tracking control. In lateral control, kinematic model-based trajectory tracking methods include pure tracking algorithms4 and Stanley’s algorithm5. However, these methods often inadequately account for vehicle dynamics, resulting in significant model mismatch issues under conditions of large or variable curvature and medium to high speeds. This mismatch can lead to instability during the trajectory-tracking process. To enhance the vehicle’s tracking performance under such conditions, it is essential to incorporate vehicle dynamics into the controller design. The trajectory tracking controllers based on the dynamics model include PID control6, LQR control7, sliding mode control8,9,10,11, fuzzy control12, model predictive control13, etc. Although some results have been achieved in some previous research, there are still some challenges, which mainly lie in the highly nonlinear nature of the vehicle dynamics model and the interference of time-varying parameters; and the trade-off between the computational efficiency and the accuracy of the vehicle model14. In longitudinal control, PID is widely used in industry because it does not depend on the accurate model and the control principle is simple, in addition, sliding mode adaptive speed control15, optimal pre-scanning speed tracking control16, MPC speed tracking control17 and so on in vehicle speed tracking control have all have achieved certain results, but the working conditions involved are relatively simple for the nonlinear characteristics of tires and the longitudinal coupling characteristics of the vehicle are relatively insufficient consideration. Therefore, we expect to design stable, reliable, accurate, fast, and robust lateral and longitudinal controllers based on the trajectory tracking control of automated vehicles.

In this paper, we design and compare three lateral control schemes, namely LQR, MPC, and NISMC to track the reference trajectory. For longitudinal control, we design and compare two schemes: MPC speed tracking control and PID control to track the reference vehicle speed. The main contributions of this paper are as follows:

  1. 1.

    Three kinds of lateral controllers, LQR, MPC, and NISMC, are designed based on a three-degree-of-freedom vehicle model and a tracking error model. The current design enhances the feedforward link in conjunction with feedback control to eliminate steady-state lateral displacement errors, thereby improving control accuracy. Secondly, a linear time-varying MPC controller is developed, employing a QP solver to process the objective function with constraints for effective trajectory tracking. Finally, a nonlinear integral sliding mode lateral controller is proposed, building upon traditional sliding mode control. This new controller achieves zero steady-state error by replacing the sign function with a saturation function while incorporating integral action.

  2. 2.

    In order to achieve longitudinal motion control for trajectory tracking, an MPC speed-tracking controller is designed. Through a layered control approach, the upper layer calculates the desired acceleration based on the current speed, current acceleration, and desired speed, and then transmits this information to the lower layer. The lower layer is governed by a drive-brake switching logic and a PI controller to generate the drive-brake input necessary for effective speed tracking. Additionally, a PID controller is employed as a benchmark to compare the control effectiveness of the two controllers.

The remainder of the paper is organized as follows: “Model description” describes the model, specifically deriving the vehicle dynamics model and the tracking error model. “Lateral controller design” details the design of the lateral controller using LQR, MPC, and NISMC based on the established model. “Longitudinal controller design” outlines the design of the longitudinal controller utilizing MPC and PID control. “Simulation results and discussion” demonstrates the control performance of each controller through simulation analysis and quantifies the results in combination with the six-dimensional score graph for comprehensive evaluation. Finally, conclusions are presented in “Conclusion”.

Model description

As shown in Fig. 114, this section presents the design of the 3DOF vehicle dynamic model and a tracking error model for further analysis and the development of a corresponding control strategy.

Fig. 1
figure 1

Dynamic modeling of trajectory tracking systems14.

Vehicle dynamics model

To ensure a better characterization of vehicle dynamics, as well as to enhance the accuracy and responsiveness of trajectory tracking, this study employs a three-degree-of-freedom dynamics model for vehicles. The equations of motion18 in the longitudinal, lateral, and transverse pendulum directions are formulated based on Newton’s second law, which is expressed as follows:

$$\begin{gathered} m\left( {\dot{v}_{x} - v_{y} \gamma } \right) = F_{x} - F_{yf} \sin \delta_{f} - F_{r} - F_{w} - F_{g} - F_{j} \hfill \\ m\left( {\dot{v}_{y} + v_{x} \gamma } \right) = F_{yf} \cos \delta_{f} + F_{yr} \hfill \\ I_{z} \dot{\gamma } = l_{f} F_{yf} \cos \delta_{f} - l_{r} F_{yr} \hfill \\ \end{gathered}$$
(1)

where m represents the mass of the vehicle; γ is the yaw angular velocity of the vehicle; vx, vy are the longitudinal and lateral velocities of the vehicle, respectively; Fx is the total tire force along the longitudinal axis of the vehicle; Fr is the rolling resistance, Fw is the air resistance, Fg is the ramp resistance, and Fj is the acceleration resistance; Fyf, Fyr are the lateral tire forces of the front and rear wheels; lf, lr are the distances from the center of mass to the front and rear axles; and δf denotes the angle of the front wheels; Iz signifies the yaw moment of inertia.

Where rolling resistance, air resistance, slope resistance, and acceleration resistance19 are expressed as follows:

$$\begin{gathered} F_{r} = mgf \hfill \\ F_{w} = \frac{{C_{D} Av_{x}^{2} }}{21.15} \hfill \\ F_{g} = mg\sin \theta_{g} \hfill \\ F_{j} = \tau m\frac{dV}{{dt}} \hfill \\ \end{gathered}$$
(2)

where f denotes the rolling resistance coefficient, CD is the air resistance coefficient, A represents the vehicle windward area, \({\theta }_{g}\) is the measured or estimated road slope, \(\tau\) signifies the conversion coefficient of the vehicle rotating mass, \(\tau >1\), \(\frac{dV}{dt}\) is the vehicle driving speed.

According to the wheel torque balance relationship, the equation governing wheel dynamics can be derived as follows:

$$I_{\omega i} \dot{\omega } = T_{di} - T_{bi} - F_{xi} R - F_{Ri} R$$
(3)

where \({I}_{\omega i}\) is the moment of inertia of the wheel, \(\upomega\) is the angular speed of the wheel, R signifies the equivalent rolling radius of the wheel, \({T}_{di}\) and \({T}_{bi}\) respectively denote the driving torque and braking torque of the wheel, \({F}_{xi}\) is the longitudinal tire force of the wheel, and \({F}_{Ri}\) is the rolling resistance of the wheel.

Because the nonlinear model impacts the computational complexity of the controller, it has been further simplified. First, we assume that the front wheel angle is small. Second, the tire model is simplified to represent a linear relationship between the tire side deflection force and the side deflection angle. The side force20 is expressed as follows:

$$\begin{gathered} F_{yf} = C_{af} \alpha_{f} \hfill \\ F_{yr} = C_{ar} \alpha_{r} \hfill \\ \end{gathered}$$
(4)

where Caf represents the lateral stiffness of the front wheel and Car denotes the lateral stiffness of the rear wheel. αf is the side deflection angle of the front wheel, and αr is the side deflection angle of the rear wheel.

The front and rear wheel side deflections of the vehicle are determined using the small angle assumption as follows:

$$\begin{gathered} \alpha_{f} = \frac{{v_{y} + l_{f} \gamma }}{{v_{x} }} - \delta_{f} \hfill \\ \alpha_{r} = \frac{{v_{y} - l_{r} \gamma }}{{v_{x} }} \hfill \\ \end{gathered}$$
(5)

Considering that the lateral declination angle and yaw velocity of the center of mass effectively represent the lateral stability of the vehicle, the lateral dynamics model is derived from the force balance equation perpendicular to the vehicle’s longitudinal axis and the moment balance equation around the center of mass:

$$\left( {\begin{array}{*{20}c} {\dot{v}_{y} } \\ {\dot{\beta }} \\ {\dot{\gamma }} \\ \end{array} } \right) = \left( {\begin{array}{*{20}c} {\frac{{C_{af} {\text{ + C}}_{ar} }}{{mv_{x} }}} & 0 & {\frac{{l_{f} C_{af} - l_{r} C_{ar} }}{{mv_{x} }}} \\ 0 & {\frac{{C_{af} {\text{ + C}}_{ar} }}{{mv_{x} }}} & {\frac{{l_{f} C_{af} - l_{r} C_{ar} }}{{mv_{x}^{2} }} - 1} \\ 0 & {\frac{{l_{f} C_{af} - l_{r} C_{ar} }}{{I_{z} }}} & {\frac{{l_{f}^{2} C_{af} + l_{r}^{2} C_{ar} }}{{I_{z} v_{x} }}} \\ \end{array} } \right)\left( {\begin{array}{*{20}c} {v_{y} } \\ \beta \\ \gamma \\ \end{array} } \right) + \left( {\begin{array}{*{20}c} { - \frac{{C_{af} }}{m}} \\ { - \frac{{C_{af} }}{m}} \\ { - \frac{{l_{f} C_{af} }}{{I_{z} }}} \\ \end{array} } \right)\delta_{f}$$
(6)

where \(\beta\) is the centroid side deflection angle of the vehicle.

Tracking error model

The tracking error model is a fundamental concept in vehicle trajectory tracking control. For a vehicle to achieve autonomous navigation and driving along a predetermined trajectory or path, the tracking error model aids in understanding the discrepancies that arise when the vehicle follows the reference trajectory. This understanding is essential for designing an appropriate controller that minimizes these errors and enhances tracking performance.

As illustrated in Fig. 1, the lateral error \(y_{e}\) is defined as the straight-line distance from the vehicle’s center of mass to the point where the reference trajectory is projected. The heading deviation is expressed as follows:

$$\varphi_{e} = \varphi - \varphi_{d}$$
(7)

where \(\varphi\) and \(\varphi_{d}\) are the heading angles of the longitudinal axis of the body and the tangent to the reference track at point P, respectively.

For lateral velocity error \(\dot{{y}_{e}}\) and lateral acceleration error \(\ddot{{y}_{e}}\) satisfy the relationship:

$$\begin{gathered} \dot{y}_{e} = v_{x} \varphi_{e} + v_{y} \hfill \\ \ddot{y}_{e} = v_{x} \dot{\varphi }_{e} + \dot{v}_{y} \hfill \\ \end{gathered}$$
(8)

When the effect of the heading angular acceleration error is disregarded under conditions of small curvature, the heading angular velocity error and the heading angular acceleration error exhibit the following relationship:

$$\begin{gathered} \dot{\varphi }_{e} = \dot{\varphi } - \dot{\varphi }_{d} \hfill \\ \ddot{\varphi }_{e} = \ddot{\varphi } - \ddot{\varphi }_{d} \hfill \\ \end{gathered}$$
(9)

The state equation is formulated based on the vehicle’s trajectory tracking error. The state variables are defined as the lateral tracking error ye, heading error φe, lateral speed error \(\dot{{y}_{e}}\), heading angular speed error \(\dot{{\varphi }_{e}}\), and the input variable is the front wheel angle δf. By integrating the vehicle dynamics relations with the error calculation equations, the trajectory tracking state equation can be derived as follows:

$$\begin{gathered} \dot{x} = Ax + Bu + C\dot{\varphi }_{d} \hfill \\ y = Dx \hfill \\ \end{gathered}$$
(10)

In Eq. (10), error space state equation \(x={\left[\begin{array}{ccc}{y}_{e}& \begin{array}{cc}\dot{{y}_{e}}& {\varphi }_{e}\end{array}& \dot{{\varphi }_{e}}\end{array}\right]}^{T}\), input variables \(u={\delta }_{f}\), output variable \(y={\left[\begin{array}{cc}{y}_{e}& {\varphi }_{e}\end{array}\right]}^{T}\), and the specific forms of each matrix A, B, C and D are expressed as

$$\begin{gathered} A = \left[ {\begin{array}{*{20}c} 0 & 1 & 0 & 0 \\ 0 & {\frac{{C_{af} {\text{ + C}}_{ar} }}{{mv_{x} }}} & { - \frac{{C_{af} {\text{ + C}}_{ar} }}{m}} & {\frac{{l_{f} C_{af} - l_{r} C_{ar} }}{{mv_{x} }}} \\ 0 & 0 & 0 & 1 \\ 0 & {\frac{{l_{f} C_{af} - l_{r} C_{ar} }}{{I_{z} v_{x} }}} & { - \frac{{l_{f} C_{af} - l_{r} C_{ar} }}{{I_{z} }}} & {\frac{{l_{f}^{2} C_{af} + l_{r}^{2} C_{ar} }}{{I_{z} v_{x} }}} \\ \end{array} } \right] \hfill \\ \hfill \\ \hfill \\ B = \left[ {\begin{array}{*{20}c} 0 \\ { - \frac{{C_{af} }}{m}} \\ 0 \\ { - \frac{{l_{f} C_{af} }}{{I_{z} }}} \\ \end{array} } \right], \, C = \left[ {\begin{array}{*{20}c} 0 \\ {\frac{{l_{f} C_{af} - l_{r} C_{ar} }}{{mv_{x} }} - v_{x} } \\ 0 \\ {\frac{{l_{f}^{2} C_{af} + l_{r}^{2} C_{ar} }}{{I_{z} v_{x} }}} \\ \end{array} } \right],D = \left[ {\begin{array}{*{20}c} 1 & 0 & 0 & 0 \\ 0 & 0 & 1 & 0 \\ \end{array} } \right] \hfill \\ \end{gathered}$$
(11)

Lateral controller design

In this section, we will design LQR, MPC, and NISMC controllers based on the trajectory tracking model established earlier. By comparing the three lateral control methods, we will assess the effectiveness of each controller. This evaluation will be based on several criteria, including trajectory tracking accuracy, robustness to parameter uncertainty, reliability in handling curvature discontinuities, and the actual control input.

LQR controller design

As the optimal control, the LQR control algorithm has a relatively stable control effect. It can effectively reduce system error to zero using minimal control input while simultaneously stabilizing unstable systems. The closed-loop optimal control system is established through an all-state linear feedback control law. The linear quadratic optimal control problem has a standardized solution process, allowing for the derivation of an analytical expression for the optimal solution, which can incorporate various performance indicators21. Consequently, this paper applies the LQR controller to the design of a lateral controller.

Theoretical basis of LQR trajectory tracking control

LQR controller comprises several components: the AB calculation module, the LQR module, the prediction module, the tracking error calculation module, the feedforward control calculation module, and the optimal control module. Initially, the optimal control feedback matrix K is obtained by calculating the vehicle dynamics parameters AB and inputting them into the LQR module. Subsequently, to ensure control smoothness and enhance accuracy, the dynamic information obtained from the prediction module is augmented. The status information is gathered by the tracking error calculation module, and the optimal control rate is calculated by the optimal control module. Finally, based on the original control law, an appropriate feedforward control quantity is added to eliminate the steady-state error in lateral displacement. Fig. 2 illustrates the algorithmic flow of the LQR trajectory tracking controller.

Fig. 2
figure 2

Algorithmic flow of LQR lateral controller

Consider a linear error system:

$$\dot{x} = Ax + Bu + C\dot{\varphi }_{d}$$
(12)

By establishing the optimal control \({u}^{\boldsymbol{*}}\left(t\right)\), the quadratic performance index cost function is minimized:

$$J = \frac{1}{2}\int_{0}^{\infty } {\left[ {x^{T} \left( t \right)Qx\left( t \right) + u^{T} \left( t \right)Ru\left( t \right)} \right]} dt$$
(13)

where Q is a 4 × 4 semi-definite real symmetric constant matrix, reflecting the weight of the state quantity, and R is a Positive definite matrix, reflecting the weight of the control quantity. Through iterative tuning to obtain the weight matrices \(Q=diag\left\{30, 1, 5, 1\right\}\), \(R=10\).

Constructing Hamilton function:

$$H = - \frac{1}{2}\left[ {x^{T} \left( t \right)Qx\left( t \right) + u^{T} \left( t \right)Ru\left( t \right)} \right] + \lambda^{T} \left[ {Ax\left( t \right) + Bu\left( t \right)} \right]$$
(14)

Ignoring the constraints of the input signal, the derivation of Eq. (14) is conducted to determine the extreme value, allowing the optimal control to be expressed as follows:

$$u^{ * } \left( t \right) = R^{ - 1} B^{T} \lambda \left( t \right)$$
(15)

where \(\lambda \left( t \right) = P\left( t \right)x\left( t \right)\), P is the positive definite solution of the Riccati equation:

$$PA + A^{T} P - PBR^{ - 1} BP^{T} + Q = 0$$
(16)

The necessary and sufficient conditions for obtaining the optimal control signal are as follows:

$$\begin{gathered} \, u^{ * } \left( t \right) = - Kx\left( t \right) \hfill \\ K = R^{ - 1} B^{T} P{ , }K = \left[ {\begin{array}{*{20}c} {K_{1} } & {K_{2} } & {K_{3} } & {K_{4} } \\ \end{array} } \right] \hfill \\ \end{gathered}$$
(17)

Application of LQR in trajectory tracking control

For LQR, in order to facilitate calculation and avoid multi-value problems, the expected trajectory is discretized to obtain a series of reference trajectory points22, as shown in Fig. 3.

Fig. 3
figure 3

Schematic of discrete reference trajectory points22.

The error matrix and curvature of discrete trace points are calculated as follows:

  1. 1.

    At any given time, the tuple of reference track points is represented by \(\left[\begin{array}{cc}\begin{array}{cc}{x}_{d}& {y}_{d}\end{array}& \begin{array}{cc}{\varphi }_{d}& {k}_{d}\end{array}\end{array}\right]\), traversing reference track point \(\left[\begin{array}{cc}\begin{array}{cc}{x}_{d}& {y}_{d}\end{array}& \begin{array}{cc}{\varphi }_{d}& {k}_{d}\end{array}\end{array}\right]\) to find the closest point to the real position \(\left[\begin{array}{cc}\begin{array}{cc}x& y\end{array}& \begin{array}{cc}\varphi & k\end{array}\end{array}\right]\) of the vehicle, which is called the matching point. Define the sequence where the matching points are located as \(\left[\begin{array}{cc}\begin{array}{cc}{x}_{m}& {y}_{m}\end{array}& \begin{array}{cc}{\varphi }_{m}& {k}_{m}\end{array}\end{array}\right]\) and the unit tangent vector and normal vector of the matching points are expressed as

    $$\begin{gathered} \vec{\tau }_{m} = \left[ {\begin{array}{*{20}c} {\cos \left( {\varphi_{m} } \right)} \\ {\sin \left( {\varphi_{m} } \right)} \\ \end{array} } \right] \hfill \\ \vec{n}_{m} = \left[ {\begin{array}{*{20}c} { - \sin \left( {\varphi_{m} } \right)} \\ {\cos \left( {\varphi_{m} } \right)} \\ \end{array} } \right] \hfill \\ \end{gathered}$$
    (18)
  2. 2.

    Let the curvature from the matching point to the projection point remain unchanged. According to the geometric relationship, the longitudinal position deviation and lateral displacement error can be obtained as follows:

    $$\begin{gathered} x_{e} = - \left( {x - x_{m} } \right)\cos \varphi_{m} + \left( {y - y_{m} } \right)\sin \varphi_{m} \hfill \\ y_{e} = - \left( {x - x_{m} } \right)\sin \varphi_{m} + \left( {y - y_{m} } \right)\cos \varphi_{m} \hfill \\ \end{gathered}$$
    (19)
  3. 3.

    Define s as the arc length between point P and a reference point on the reference track. The speed of point P moving along the reference track, denoted as s, can be expressed as:

    $$\dot{s} = \frac{1}{{1 - k_{d} y_{e} }}\left( {v_{x} \cos \varphi_{e} + v_{y} \sin \varphi_{e} } \right) = \frac{{V\cos \left( {\varphi - \varphi_{e} } \right)}}{{1 - k_{d} y_{e} }}$$
    (20)
  4. 4.

    The expected course angle can be obtained from the definitions of curvature and arc length, measured from the matching point to the projection point:

    $$\varphi_{d} = \varphi_{m} + k_{m} x_{e}$$
    (21)
  5. 5.

    The course deviation can be determined based on the course angle at the projection point. The derivatives of course deviation and velocity deviation are expressed as follows:

    $$\begin{gathered} \varphi_{e} = \varphi - \varphi_{d} \hfill \\ \dot{y}_{e} = v_{y} \cos \varphi_{e} + v_{x} \sin \varphi_{e} = V\sin \left( {\varphi - \varphi_{d} } \right) \hfill \\ \dot{\varphi }_{d} = k_{d} \dot{s} = k_{m} \dot{s} \hfill \\ \dot{\varphi }_{e} = \dot{\varphi } - k_{m} \frac{{v_{x} \cos \varphi_{e} - v_{y} \sin \varphi_{e} }}{{1 - k_{m} y_{e} }} \hfill \\ \end{gathered}$$
    (22)

Finally, the error space state \(x={\left[\begin{array}{ccc}{y}_{e}& \begin{array}{cc}\dot{{y}_{e}}& {\varphi }_{e}\end{array}& \dot{{\varphi }_{e}}\end{array}\right]}^{T}\) and the curvature kd are obtained. To further enhance real-time performance and operational smoothness, while considering the hysteresis of the algorithm, the prediction time is defined as tm. The position after tm is predicted in advance, and this prediction information is updated to the discrete trajectory reference point to obtain the control quantity at the subsequent moment. The forecast information is expressed as follows:

$$\begin{gathered} x_{pre} = x + v_{x} t_{m} \cos \varphi - v_{y} t_{m} \sin \varphi \hfill \\ y_{pre} = y + v_{y} t_{m} \cos \varphi + v_{x} t_{m} \sin \varphi \hfill \\ \varphi_{pre} = \varphi + \dot{\varphi }t_{m} \hfill \\ v_{{x_{pre} }} = v_{x} \hfill \\ v_{{y_{pre} }} = v_{y} \hfill \\ \dot{\varphi }_{pre} = \dot{\varphi } \hfill \\ \end{gathered}$$
(23)

where \({x}_{pre}, {y}_{pre},{\varphi }_{pre},{v}_{{x}_{pre}},{v}_{{y}_{pre}},{\dot{\varphi }}_{pre}\) are respectively the predicted lateral and longitudinal position, yaw angle, lateral and longitudinal velocity, and yaw angle velocity.

In order to improve the response speed of the trajectory tracking control system to the reference signal and reduce the lateral steady-state error, a feedforward control strategy is introduced. This approach enables the system to better handle various complex conditions, improves control performance, reduces steady-state error, and achieves the desired control effect. The feedforward control law is defined as follows:

$$u = - Kx + \delta$$
(24)

Substituting into the state-space equation of the system, there is:

$$\dot{x} = Ax + B\left( { - Kx + \delta } \right) + C\dot{\varphi }_{d}$$
(25)

When the system is stabilized, there is:

$$x = - \left( {A - BK} \right)^{ - 1} \left( {B\delta + C\dot{\varphi }_{d} } \right)$$
(26)

Let = 0, the appropriate feedforward control quantity is expressed as follows:

$$\delta = k_{d} \left[ {l_{f} + l_{r} - l_{r} K_{3} - \frac{{mv_{x}^{2} }}{{l_{f} + l_{r} }}\left( {\frac{{l_{r} }}{{C_{af} }} + \frac{{l_{f} }}{{C_{ar} }}K_{3} - \frac{{l_{f} }}{{C_{ar} }}} \right)} \right]$$
(27)

where kd is the path curvature and K3 is the third term of the optimal control law feedback matrix.

MPC controller design

The MPC controller exhibits high adaptability in the realm of intelligent vehicle motion control, as it systematically incorporates predictive information and addresses multiple constraints and multi-objective optimization challenges. However, due to the computational speed limitations of MPC when handling nonlinear model optimization problems, this paper employs linear parameter varying model predictive control (LPV-MPC) to ensure both tracking accuracy and real-time computation23.

Model discretization and augmented system representation

The MPC trajectory tracking controller is founded on the dynamics model of tracking error. To facilitate the design of the MPC algorithm, it is necessary to discretize the tracking error dynamics model. In this context, the vehicle model, after discretization, is expressed using the midpoint Euler method as follows:

$$\begin{gathered} x\left( {k + 1} \right) = A_{1} x\left( k \right) + B_{1} u\left( k \right) + C_{2} \hfill \\ y\left( k \right) = D_{1} x\left( k \right) \hfill \\ \end{gathered}$$
(28)

where \({A}_{1}={\left(I-\frac{AT}{2}\right)}^{-1}\left(I+\frac{AT}{2}\right)\), \({B}_{1}=BT\), \({C}_{2}=C\dot{{\varphi }_{d}}T\), \({D}_{1}=D\) and T is the sampling time.

In general, in order to eliminate steady-state error and ensure vehicle stationarity, the constraint of control increment should be considered. From \(\Delta u\left(k\right)=u\left(k\right)-u\left(k-1\right)\), state quantity \(x\left(k\right)\) and control quantity \(u\left(k\right)\) are augmented into a new state variable, which is represented as \(\xi \left(k\right)={\left[\begin{array}{cc}x\left(k\right)& u\left(k-1\right)\end{array}\right]}^{\text{T}}\). The augmented system is represented as follows:

$$\begin{gathered} \xi \left( {k + 1} \right) = \tilde{A}\xi \left( k \right) + \tilde{B}\Delta u\left( k \right) + \tilde{C} \hfill \\ y\left( k \right) = \tilde{D}\xi \left( k \right) \hfill \\ \end{gathered}$$
(29)

In which:

$$\tilde{A} = \left[ {\begin{array}{*{20}c} {A_{1} } & {B_{1} } \\ 0 & I \\ \end{array} } \right],\tilde{B} = \left[ {\begin{array}{*{20}c} {B_{1} } \\ I \\ \end{array} } \right],\tilde{C} = \left[ {\begin{array}{*{20}c} {C_{2} } \\ 0 \\ \end{array} } \right],\tilde{D} = \left[ {\begin{array}{*{20}c} {D_{1} } & 0 \\ \end{array} } \right]$$
(30)

Define the input increment and the output representation at future moments as follows:

$$Y\left( k \right) = \left[ {\begin{array}{*{20}c} {y\left( {k{ + }1} \right)} \\ {y\left( {k{ + }2} \right)} \\ \vdots \\ {y\left( {k{ + }N_{p} } \right)} \\ \end{array} } \right],\Delta U\left( k \right) = \left[ {\begin{array}{*{20}c} {\Delta u\left( k \right)} \\ {\Delta u\left( {k + 1} \right)} \\ \vdots \\ {\Delta u\left( {k + N_{c} - 1} \right)} \\ \end{array} } \right]$$
(31)

The states in the predicted time domain are calculated iteratively using the generalized discrete state space equations as follows:

$$\begin{gathered} \xi \left( {k + 1} \right) = \tilde{A}\xi \left( k \right) + \tilde{B}\Delta u\left( k \right) + \tilde{C} \hfill \\ \xi \left( {k + 2} \right) = \tilde{A}^{2} \xi \left( k \right) + \tilde{A}\tilde{B}\Delta u\left( k \right) + \tilde{B}\Delta u\left( {k + 1} \right) + \tilde{A}\tilde{C} + \tilde{C} \hfill \\ \vdots \hfill \\ \xi \left( {k + N_{c} } \right) = \tilde{A}^{{N_{c} }} \xi \left( k \right) + \tilde{A}^{{N_{c} - 1}} \tilde{B}\Delta u\left( k \right) + \cdots \hfill \\ \, + \tilde{B}\Delta u\left( {k + N_{c} - 1} \right) + \tilde{A}^{{N_{c} - 1}} \tilde{C} + \cdots + \tilde{C} \hfill \\ \vdots \hfill \\ \xi \left( {k + N_{p} } \right) = \tilde{A}^{{N_{p} }} \xi \left( k \right) + \tilde{A}^{{N_{p} - 1}} \tilde{B}\Delta u\left( k \right) + \cdots \hfill \\ \, + \tilde{A}^{{N_{p} - N_{c} }} \tilde{B}\Delta u\left( {k + N_{c} - 1} \right) + \tilde{A}^{{N_{p} - N_{c} }} \tilde{C} + \cdots + \tilde{C} \hfill \\ \end{gathered}$$
(32)

where Np and Nc represent the prediction and control time domains, respectively. Moreover \({N}_{c}\le {N}_{p}\), the output in the predicted time domain can be obtained according to the iteration as follows:

$$\begin{gathered} y\left( {k + 1} \right) = \tilde{D}\tilde{A}\xi \left( k \right) + \tilde{D}\tilde{B}\Delta u\left( k \right) + \tilde{D}\tilde{C} \hfill \\ y\left( {k + 2} \right) = \tilde{D}\tilde{A}^{2} \xi \left( k \right) + \tilde{D}\tilde{A}\tilde{B}\Delta u\left( k \right) + \tilde{D}\tilde{B}\Delta u\left( {k + 1} \right) + \tilde{D}\tilde{A}\tilde{C} + \tilde{D}\tilde{C} \hfill \\ \vdots \hfill \\ y\left( {k + N_{c} } \right) = \tilde{D}\tilde{A}^{{N_{c} }} \xi \left( k \right) + \tilde{D}\tilde{A}^{{N_{c} - 1}} \tilde{B}\Delta u\left( k \right) + \cdots \hfill \\ \, + \tilde{D}\tilde{B}\Delta u\left( {k + N_{c} - 1} \right) + \tilde{D}\tilde{A}^{{N_{c} - 1}} \tilde{C} + \cdots + \tilde{D}\tilde{C} \hfill \\ \vdots \hfill \\ y\left( {k + N_{p} } \right) = \tilde{D}\tilde{A}^{{N_{p} }} \xi \left( k \right) + \tilde{D}\tilde{A}^{{N_{p} - 1}} \tilde{B}\Delta u\left( k \right) + \cdots \hfill \\ \, + \tilde{D}\tilde{A}^{{N_{p} - N_{c} }} \tilde{B}\Delta u\left( {k + N_{c} - 1} \right) + \tilde{D}\tilde{A}^{{N_{p} - N_{c} }} \tilde{C} + \cdots + \tilde{D}\tilde{C} \hfill \\ \end{gathered}$$
(33)

Organizing Eq. (33) yields the predicted output as follows:

$$Y\left( k \right) = \Psi \xi \left( k \right) + \Phi \Delta U\left( k \right) + \Gamma \Theta \left( k \right)$$
(34)

With:

$$\begin{gathered} \Psi = \left[ {\begin{array}{*{20}c} {\tilde{D}\tilde{A}} \\ {\tilde{D}\tilde{A}^{2} } \\ \vdots \\ {\tilde{D}\tilde{A}^{{N_{c} }} } \\ \vdots \\ {\tilde{D}\tilde{A}^{{N_{p} }} } \\ \end{array} } \right],\Phi = \left[ {\begin{array}{*{20}c} {\tilde{D}\tilde{B}} & 0 & \cdots & 0 \\ {\tilde{D}\tilde{A}\tilde{B}} & {\tilde{D}\tilde{B}} & \cdots & \vdots \\ \vdots & \vdots & \cdots & 0 \\ {\tilde{D}\tilde{A}^{{N_{c} - 1}} \tilde{B}} & {\tilde{D}\tilde{A}^{{N_{c} - 2}} \tilde{B}} & \cdots & {\tilde{D}\tilde{B}} \\ \vdots & \vdots & \cdots & \vdots \\ {\tilde{D}\tilde{A}^{{N_{p} - 1}} \tilde{B}} & {\tilde{D}\tilde{A}^{{N_{p} - 2}} \tilde{B}} & \cdots & {\tilde{D}\tilde{A}^{{N_{p} - N_{c} }} \tilde{B}} \\ \end{array} } \right] \hfill \\ \Gamma = \left[ {\begin{array}{*{20}c} {\tilde{C}} \\ {\tilde{C}} \\ \vdots \\ {\tilde{C}} \\ \end{array} } \right],\Theta \left( k \right) = \left[ {\begin{array}{*{20}c} {\tilde{D}} & 0 & \cdots & 0 \\ {\tilde{D}\tilde{A}} & {\tilde{D}} & \cdots & 0 \\ {\tilde{D}\tilde{A}^{2} } & {\tilde{D}\tilde{A}} & \cdots & 0 \\ \vdots & \vdots & \ddots & \vdots \\ {\tilde{D}\tilde{A}^{{N_{p} - 1}} } & {\tilde{D}\tilde{A}^{{N_{p} - 2}} } & \cdots & {\tilde{D}} \\ \end{array} } \right] \hfill \\ \end{gathered}$$
(35)

Finally, the discretization of the model makes the model suit the MPC algorithm in the system. Moreover, enhancing the system representation improves the performance and adaptability of MPC control. Through these operations, we establish a more accurate and efficient foundational model for the application of MPC in trajectory tracking control.

Application of MPC in trajectory tracking control

In order to enable the MPC trajectory tracking controller to follow the reference path smoothly and accurately within the prediction time domain, while also accounting for potential errors that may arise during actual tracking, errors that could hinder the timely identification of the optimal solution, a relaxation factor ρ is introduced24. The cost function is defined as follows:

$$J\left( {\xi \left( k \right),\Delta U\left( k \right),\rho } \right) = \mathop \sum \limits_{i = 1}^{{N_{p} }} \left\| {y\left( {k + i} \right) - y_{ref} \left( {k + i} \right)} \right\|_{{\tilde{Q}}}^{2} {\kern 1pt} + \mathop \sum \limits_{i = 0}^{{N_{c} - 1}} \left\| {\Delta u\left( {k + i} \right)} \right\|_{{\tilde{R}}}^{2} + \varepsilon^{2} \rho$$
(36)

where \(\varepsilon\) is the weight coefficient of the relaxation factor, and the diagonal matrices \(\widetilde{Q}\) and \(\widetilde{R}\) are positive definite weight matrices, where \(\widetilde{Q}\) represents the tracking error between the predicted output and the reference trajectory, and \(\widetilde{R}\) is a penalty on the control inputs, which helps to make the control process smoother.

Substituting the predicted output into the cost function:

$$\begin{gathered} J\left( {\xi \left( k \right),\Delta U\left( k \right),\rho } \right) = \left( {Y\left( k \right) - Y_{ref} \left( k \right)} \right)^{T} \tilde{Q}\left( {Y\left( k \right) - Y_{ref} \left( k \right)} \right) + \Delta U^{T} \left( k \right)\tilde{R}\Delta U\left( k \right) + \varepsilon^{2} \rho \\ = \left( {G + \Phi \Delta U\left( k \right)} \right)^{T} \tilde{Q}\left( {G + \Phi \Delta U\left( k \right)} \right) + \Delta U^{T} \left( k \right)\tilde{R}\Delta U\left( k \right) + \varepsilon^{2} \rho \\ = G^{T} \tilde{Q}G + \left( {\Phi \Delta U\left( k \right)} \right)^{T} \tilde{Q}\left( {\Phi \Delta U\left( k \right)} \right) + 2G^{T} \tilde{Q}\left( {\Phi \Delta U\left( k \right)} \right) \\ \, + \Delta U^{T} \left( k \right)\tilde{R}\Delta U\left( k \right) + \varepsilon^{2} \rho \\ \end{gathered}$$
(37)

where \(G\left(k\right)=\psi \xi \left(k\right)+\Gamma \Theta \left(k\right)\), and \({G}^{T}\left(k\right)\widetilde{Q}G\left(k\right)\) are constants independent of \(\Delta U\). The cost function is expressed as

$$\begin{gathered} J\left( {\xi \left( k \right),\Delta U\left( k \right),\rho } \right) = \Delta U^{T} \left( k \right)\left( {\Phi^{T} \tilde{Q}\Phi + \tilde{R}} \right)\Delta U\left( k \right) + \varepsilon^{2} \rho + 2G^{T} \left( k \right)\tilde{Q}\Phi \Delta U\left( k \right) \\ = \frac{1}{2}\Delta U^{T} \left( k \right)H\Delta U\left( k \right) + g^{T} \Delta U\left( k \right) \\ \end{gathered}$$
(38)

where \(H = 2\left[ {\begin{array}{*{20}c} {\left( {\Phi^{T} \tilde{Q}\Phi + \tilde{R}} \right)} & 0 \\ 0 & \varepsilon \\ \end{array} } \right],g^{T} = \left[ {\begin{array}{*{20}c} {2\Phi^{T} \tilde{Q}G\left( k \right)} & 0 \\ \end{array} } \right].\)

Consider the physical constraints on the front wheel angle, specifically the rigid limitations imposed on the actuator.

$$\begin{gathered} u_{\min } \le u\left( k \right) \le u_{\max } \hfill \\ U\left( k \right){ = }{\rm P}\Delta U\left( k \right) + {\rm N}u\left( {k - 1} \right) \hfill \\ U_{\min } \le {\rm P}\Delta U\left( k \right) + {\rm N}u\left( {k - 1} \right) \le U_{\max } \hfill \\ \end{gathered}$$
(39)

In which:

$${\rm P} = \left[ {\begin{array}{*{20}c} I & 0 & \cdots & 0 \\ I & I & \cdots & 0 \\ \vdots & \vdots & \ddots & 0 \\ I & I & I & I \\ \end{array} } \right],{\rm N} = \left[ {\begin{array}{*{20}c} I \\ I \\ \vdots \\ I \\ \end{array} } \right],U\left( k \right) = \left[ {\begin{array}{*{20}c} {u\left( {k\left| k \right.} \right)} \\ {u\left( {k{ + }1\left| k \right.} \right)} \\ \vdots \\ {u\left( {k + N_{c} - 1\left| k \right.} \right)} \\ \end{array} } \right]$$
(40)

Consider the environmental conditions that impose certain restrictions on the output variables.

$$\begin{gathered} \Delta u_{\min } \le \Delta u\left( k \right) \le \Delta u_{\max } \hfill \\ \Delta U_{\min } \le \Delta U\left( k \right) \le \Delta U_{\max } \hfill \\ \end{gathered}$$
(41)

Consider that the predicted output constraint exists:

$$\begin{gathered} y_{\min } \le y \le y_{\max } \hfill \\ Y_{\min } \le \Psi \xi \left( k \right) + \Phi \Delta U\left( k \right) + \Gamma \Theta \left( k \right) \le Y_{\max } \hfill \\ \end{gathered}$$
(42)

The MPC trajectory tracking problem is reformulated as a quadratic programming problem by defining appropriate cost functions and constraints. QuadProg, a widely used quadratic programming solver, efficiently and accurately addresses the optimization problem. The optimization is solved at any time step k, and the optimal solution \(\Delta {u}^{*}\left(k\right)\) is obtained and applied to the system to obtain the optimal control law:

$$u\left( k \right) = \Delta u^{ * } \left( k \right) + u\left( {k - 1} \right)$$
(43)

In this design, in order to ensure the accuracy of the acquired vehicle information set the adoption time T to be 0.02. To improve the computational efficiency, set the prediction step size \({N}_{p}=20\) and the control step size \({N}_{c}=3\). Through iterative tuning to obtain the weight matrices \(\widetilde{Q}=diag\left\{20,0; 0,5\right\}\), \(\widetilde{R}=600\), the weights of the relaxation factors \(\upvarepsilon =10\).

Design of nonlinear conditional integral sliding mode controller

Sliding mode control is widely utilized in intelligent driving motion control due to its inherent discontinuity in the sliding mode surface25, which provides significant robustness against external perturbations and variations in system modeling parameters. However, when confronted with switching delays or high-frequency dynamics, jitter phenomena may arise, adversely affecting the tracking performance. To address this issue, this paper introduces the third lateral controller NISMC26, which effectively eliminates steady-state errors caused by model inaccuracies or external disturbances, thanks to its lower feedback gain. In comparison to the basic sliding mode controller, the inclusion of the integral term allows the system to rectify steady-state errors resulting from model inaccuracies or external interference, thereby ensuring accurate, smooth, and rapid tracking. Additionally, due to its low feedback gain, the controller can achieve anti-saturation of the integral operation, thereby enhancing the stability and robustness of the tracking performance.

Reference to yaw velocity calculation

From the vehicle dynamics equation of state Eq. (6), the transfer function of the second-order system relating the front wheel angle input to the transverse pendulum angular velocity response is expressed as follows:

$$\frac{\gamma \left( s \right)}{{\delta_{f} \left( s \right)}} = \frac{{b_{3} s + \left[ {a_{32} b_{1} - a_{11} b_{3} } \right]}}{{s^{2} - \left[ {a_{11} + a_{33} } \right]s + \left[ {a_{11} a_{33} - a_{23} a_{32} } \right]}}$$
(44)

With:

$$\begin{gathered} b_{1} = - \frac{{C_{af} }}{m},b_{3} = - \frac{{l_{f} C_{af} }}{{I_{z} }},a_{11} = \frac{{C_{af} {\text{ + C}}_{ar} }}{{mv_{x} }} \hfill \\ a_{23} = \frac{{l_{f} C_{af} - l_{r} C_{ar} }}{{mv_{x}^{2} }} - 1,a_{32} = \frac{{l_{f} C_{af} - l_{r} C_{ar} }}{{I_{z} }},a_{33} = \frac{{l_{f}^{2} C_{af} + l_{r}^{2} C_{ar} }}{{I_{z} v_{x} }} \hfill \\ \end{gathered}$$
(45)

The steady-state gain of the system for the front wheel angle is obtained to be designed as follows:

$$K_{g} = \left. {\frac{\gamma }{{\delta_{f} }}} \right)_{s} = \frac{{a_{31} b_{1} - a_{11} b_{3} }}{{a_{11} a_{33} - a_{23} a_{31} }} = \frac{{v_{x} }}{L}$$
(46)

Where Kg is the gain coefficient and L is the vehicle wheelbase. The reference transverse pendulum angular velocity can be expressed as:

$$\gamma_{ref} = K_{g} \delta_{f} = \frac{{v_{x} }}{{L\left( {1 + K_{w} v_{x}^{2} } \right)}}\delta_{f}$$
(47)

where Kw is the stability factor coefficient. Meanwhile, considering the limitation of the road surface condition and the small side deflection angle of the center of mass, the value of the reference transverse pendulum angular velocity limited by the road surface condition is obtained as follows27:

$$\gamma_{ref} = \left\{ \begin{gathered} K_{g} \delta_{f} ,\left| \gamma \right| \le \frac{0.85\mu g}{{v_{x} }} \hfill \\ \frac{0.85\mu g}{{v_{x} }}{\text{sgn}} \left( {\delta_{f} } \right),\left| \gamma \right| > \frac{0.85\mu g}{{v_{x} }} \hfill \\ \end{gathered} \right.$$
(48)

Application of NISMC to trajectory tracking

The design of the NISMC feedback control law is grounded in the yaw dynamics model. By regulating the front wheel angle, the vehicle’s yaw velocity is maintained, allowing it to adhere to the expected yaw velocity derived from Eq. (44). This ensures that the vehicle can navigate along the predetermined trajectory.

The yaw dynamics model obtained from Eq. (6) is expressed as follows:

$$I_{z} \gamma - \frac{{\left( {l_{f}^{2} C_{af} + l_{r}^{2} C_{ar} } \right)}}{{v_{x} }}\dot{\gamma } - \left( {l_{f} C_{af} - l_{r} C_{ar} } \right)\beta = - l_{f} C_{af} \delta_{f}$$
(49)

Defining the pendulum angle tracking error \({\gamma }_{e}=\gamma -{\gamma }_{ref}\) transforms the trajectory tracking problem into an error calibration problem:

$$\dot{\gamma }_{e} + Z\gamma_{e} = W\delta_{f} + T\beta - \dot{\gamma }_{ref} - Z\gamma_{ref}$$
(50)

With:

$$Z = - \frac{{\left( {l_{f}^{2} C_{af} + l_{r}^{2} C_{ar} } \right)}}{{I_{z} v_{x} }},W = - \frac{{l_{f} C_{af} }}{{I_{z} }},T = \frac{{\left( {l_{f} C_{af} - l_{r} C_{ar} } \right)}}{{I_{z} }}$$
(51)

To simplify the problem, we assert that by considering the centroid side deflection angle estimation error term and combining Eqs. (41) through (45), Eq. (47) can be expressed as follows:

$$\dot{\gamma }_{e} + Z\gamma_{e} = W\delta_{f} + \Delta \left( \cdot \right)$$
(52)

where \(\Delta \left(\bullet \right)\) is the combination term of the error term of centroid side deflection angle estimation and the reference yaw angle.

In order to enhance chatter reduction near the sliding mode surface, minimize tracking error, and prevent integral saturation28, a nonlinear integral sliding mode controller has been designed.

First, set up the surface of the slip mold as follows:

$$s = \gamma_{e} + k_{0} \sigma$$
(53)

where k0 is the error integral control coefficient and k0 > 0, \(\sigma\) is the integral of the error, which satisfies the relation \(\dot{\sigma }={\gamma }_{e}\). Zero steady-state error can be achieved by incorporating integral action. The derivation of the above equation exists:

$$\dot{s} = \dot{\gamma }_{e} + k_{0} \dot{\sigma } = \dot{\gamma }_{e} + k_{0} \gamma_{e}$$
(54)

The sliding mode control law can be expressed as follows:

$$\delta_{f} = \frac{{\dot{\gamma }_{e} + Z\gamma_{e} }}{W} = \frac{{ - k_{1} {\text{sgn}} \left( {\gamma_{e} } \right)}}{W} = - k_{p} {\text{sgn}} \left( {\gamma_{e} } \right)$$
(55)

In the actual control process, in order to eliminate jitter and ensure continuous smoothness in control, the saturation function \(sat\left(\bullet \right)\) instead of the sign function \(sgn\left(\bullet \right)\). The formula above can be expressed as follows:

$$\delta_{f} = - k_{p} {\text{sgn}} \left( {\frac{s}{\kappa }} \right)$$
(56)

where \(\kappa\) is the boundary layer thickness. \(sat\left(\frac{s}{\kappa }\right)\) is defined as follows:

$$sat\left( {\frac{s}{\kappa }} \right) = \left\{ \begin{gathered} {\text{sgn}} \left( {\frac{s}{\kappa }} \right), \, |\frac{s}{\kappa }| \ge 1 \hfill \\ \, \frac{s}{\kappa }, \, |\frac{s}{\kappa }| < 1 \hfill \\ \end{gathered} \right.$$
(57)

The final error is represented dynamically as:

$$\dot{\sigma } = - k_{0} \sigma + \kappa sat\left( {\frac{s}{\kappa }} \right)$$
(58)

Satisfaction \(|\sigma \left(0\right)|\le \frac{\kappa }{{k}_{0}}\).

When \(|s|\ge \kappa\), \({\delta }_{f}=-{k}_{p}sgn\left(\frac{s}{\kappa }\right)\). Therefore, outside the saturation function boundary, the front wheel angle is not influenced by the tracking error integral. The tracking error of the transverse pendulum’s angular velocity is asymptotically stabilized, which ensures both the robustness and response speed of the sliding mode control.

When \(|s|<\kappa\), \({\delta }_{f}=-{k}_{p}\frac{s}{\kappa }=-\frac{{k}_{p}}{\kappa }{\gamma }_{e}-\frac{{k}_{p}{k}_{0}}{\kappa }\sigma\). That is, following the introduction of the conditional integral within the bounds of the saturation function, the motion tracking control law incorporates an integral component of the tracking error. This addition enhances the controller’s response performance and decreases the tracking error of the transverse pendulum’s angular velocity.

Longitudinal controller design

In the trajectory tracking control of intelligent driving vehicles, it is essential to emphasize tracking accuracy, smoothness, and driving comfort while ensuring lateral control precision. Consequently, the smoothness and high accuracy of longitudinal speed control are also critical performance indicators in tracking control. As illustrated in Fig. 4, this section is based on the MPC hierarchical speed tracking controller29, where the upper layer employs the MPC controller to calculate the desired acceleration. The lower layer determines the driving and braking modes by switching logic and computes the driving or braking inputs using a simple proportional-integral control method to achieve high-precision speed tracking. Additionally, PID controllers, which are straightforward to implement and do not depend on precise vehicle models, are considered benchmarks for comparison.

Fig. 4
figure 4

MPC hierarchical speed tracking controller structure

MPC speed tracking controller design

During the longitudinal movement of the vehicle, due to the inertial delays in the drive train and control system, the first-order inertial system is considered30,31,32 in the longitudinal control denoted as follows:

$$\dot{a} = \frac{{K_{a} }}{{\tau_{d} }}\left( {a_{des} - a} \right)$$
(59)

where \({K}_{a}=1\) is the system gain; \({\tau }_{d}=0.2\) is the inertia time constant; a is the actual acceleration; ades is the desired acceleration. The space equation of state for the longitudinal motion of the vehicle can be expressed as follows:

$$\dot{\chi } = A_{s} \chi + B_{s} u_{s}$$
(60)

With:

$$A_{s} = \left[ {\begin{array}{*{20}c} 0 & 1 \\ 0 & { - \frac{1}{{\tau_{d} }}} \\ \end{array} } \right],B_{s} = \left[ {\begin{array}{*{20}c} 0 \\ {\frac{{K_{a} }}{{\tau_{d} }}} \\ \end{array} } \right]$$
(61)

where the system state vector \(\chi ={\left[\begin{array}{cc}v& a\end{array}\right]}^{T}\),control input \({u}_{s}={a}_{des}\). Using the Forward Euler method for Eq. (60), the discretized state space representation of the system can be expressed as follows:

$$\begin{gathered} \chi \left( {k + 1} \right) = A_{k} \chi \left( k \right) + B_{k} u_{s} \left( k \right) \hfill \\ \eta \left( k \right) = C_{k} \chi \left( k \right) \hfill \\ \end{gathered}$$
(62)

With:

$$A_{k} = \left[ {\begin{array}{*{20}c} 1 & T \\ 0 & {1 - \frac{T}{{\tau_{d} }}} \\ \end{array} } \right],B_{k} = \left[ {\begin{array}{*{20}c} 0 \\ {\frac{{K_{a} T}}{{\tau_{d} }}} \\ \end{array} } \right],C_{k} = \left[ {\begin{array}{*{20}c} 1 & 0 \\ \end{array} } \right]$$
(63)

To accurately and smoothly track the target velocity, the objective function is defined as follows:

$$\begin{gathered} J\left( {\chi \left( k \right),u_{s} \left( {k - 1} \right),\Delta u_{s} \left( k \right)} \right) = \mathop \sum \limits_{i = 1}^{{N_{p} }} \left\| {\eta \left( {k + i|k} \right) - \eta_{ref} \left( {k + i|k} \right)} \right\|_{{Q_{s} }}^{2} {\kern 1pt} + \\ \, \mathop \sum \limits_{i = 0}^{{N_{c} }} \left\| {\Delta u_{s} \left( {k + i} \right)} \right\|_{{R_{s} }}^{2} \\ \end{gathered}$$
(64)

where \({Q}_{s}\) is the weight matrix of the system output, reflecting the tracking accuracy of the reference speed, and \({R}_{s}\) is the weight matrix of the control input increment, reflecting the penalty for acceleration changes. The primary objective of the function is to achieve a stable and rapid speed that effectively tracks the target speed.

Considering the smoothness and comfort of driving, the constraints imposed on the control inputs and their increments are expressed as follows:

$$\begin{aligned} & u_{{s_{{\min }} }} \le u_{s} \left( {k + i} \right) \le u_{{s_{{\max }} }} \\ & \Delta u_{{s_{{\min }} }} \le \Delta u_{s} \left( {k + i} \right) \le \Delta u_{{s_{{\max }} }} \\ \end{aligned}$$
(65)

where \({u}_{smax}\) and \({u}_{smin}\) denote the maximum and minimum values of acceleration respectively, \(\Delta {u}_{smax}\) and \(\Delta {u}_{smin}\) denote the maximum and minimum values of acceleration increment respectively.

Transforming the MPC problem into a quadratic programming problem.

$$\mathop {\min }\limits_{\Delta u\left( k \right)} J\left( {\chi \left( k \right),u_{s} \left( {k - 1} \right),\Delta u_{s} \left( k \right)} \right) \to \mathop {\min }\limits_{\Delta u\left( k \right)} \frac{1}{2}\Delta u_{s}^{T} \left( k \right)H_{s} \Delta u_{s} \left( k \right) + G_{s}^{T} \Delta u_{s} \left( k \right)$$
(66)

The QP solver in MATLAB is utilized to address quadratic programming problems, and the optimal control input is determined by calculating the optimal control increment.

$$u_{s} \left( k \right) = \Delta u_{s}^{ * } \left( k \right) + u_{s} \left( {k - 1} \right)$$
(67)

The control input at time k is substituted into the system’s state-space equation. At time + 1, the system recalculates the output for the next time step based on the predicted information. It then obtains the control increment sequence for time + 1 through calculations, completing the control process of the entire system cyclically. The design weights matrix \({Q}_{s}=200\) and \({R}_{s}=0.5\).

Considering the actual situation of vehicle operation, driving, and braking are generally independent processes that do not occur simultaneously. Furthermore, to ensure a smooth driving experience, it is advisable to minimize frequent transitions between driving and braking modes. The switching buffer parameter, denoted as athr, should be carefully selected. Consequently, the design of the driving and braking switching logic is articulated as follows:

$$\begin{gathered} a_{tdes} = \left\{ \begin{gathered} a_{tdes} , \, a_{des} \ge - a_{thr} \hfill \\ 0{, }a_{des} < - a_{thr} \hfill \\ \end{gathered} \right., \hfill \\ p_{bdes} = \left\{ \begin{gathered} 0{, }a_{des} > - a_{thr} \hfill \\ p_{bdes} ,a_{des} \le - a_{thr} \hfill \\ \end{gathered} \right., \hfill \\ \end{gathered}$$
(68)

where ades is the expected acceleration, the drive or braking mode is determined by comparing with athr, atdes is the expected throttle opening, Pbdes is the expected brake master cylinder pressure.

PID speed tracking controller design

At present, PID control remains widely utilized in various longitudinal control systems due to its independence from precise modeling and its applicability to most control systems33,34. In this section, we will design a speed-tracking controller based on the PID algorithm and the control rate will be expressed as follows:

$$U_{pid} = k_{p} \Delta v + k_{i} \int {\Delta vdt + k_{d} \frac{d\Delta v}{{dt}}}$$
(69)

In the formula, proportional coefficient \({k}_{p}=1\), integral coefficient \({k}_{i}=0.001\), differential coefficient \({k}_{d}=0.1\), \(\Delta v\) is the velocity tracking error, \({U}_{pid}\) is the velocity error measurement, when \({U}_{pid}\ge 0\), apply the driving torque, when \({U}_{pid}<0\), apply the braking pressure.

Simulation results and discussion

In this section, a series of simulation experiments are conducted to compare the trajectory-tracking performance of three lateral controllers and the velocity-tracking effectiveness of two longitudinal controllers. First, “Lateral controller performance comparison” assesses the tracking performance of the three lateral controllers under variable or large curvature conditions by comparing the results of the double lane change test and the circular path test. Next, “Step speed tracking test” presents step speed-tracking tests to evaluate the speed-tracking performance of the two longitudinal controllers. Finally, “Comprehensive evaluation” analyzes the results and provides a comprehensive evaluation of the control performance of the lateral and longitudinal controllers designed in this paper. The relevant parameters of the autonomous vehicle used in this simulation are detailed in Table 1.

Table 1 Main parameters of the autonomous vehicle.

Lateral controller performance comparison

Case A: double lane change test

In this example, the automated vehicles are programmed to conduct a double lane change test at an initial speed of 36 km/h. The road surfaces are classified based on their adhesion coefficients: 0.85 for regular road conditions and 0.35 for icy or snowy conditions. The transient control capabilities and stability of the three controllers are compared under varying road environments and low lateral acceleration conditions, simulating challenging driving scenarios.

The test on the 0.85 adhesion coefficient road

The simulation results of the double lane change test conducted on a conventional high-adherence road (coefficient of friction = 0.85) are presented in Fig. 5. All three proposed controllers effectively track the reference trajectory. Among them, the LQR controller exhibits the largest maximum lateral displacement error of 0.08 m. The MPC controller has the second-largest maximum lateral displacement error, which aligns well with the reference curvature of the double lane change test, demonstrating excellent control performance. In contrast, the proposed nonlinear integral sliding mode controller achieves the smallest maximum lateral displacement error of 0.025 m. However, it is important to note that the actual steering angle of the wheel and the lateral deviation angle of the center of mass are larger, resulting in a smoother control process. While the nonlinear integral sliding mode controller provides the best tracking effect with the smallest maximum lateral displacement error of 0.025 m, it also exhibits larger actual steering angles and centroid side deflection angles, leading to a less smooth control process. In terms of heading error angles, the LQR controller achieves the smallest maximum heading error of only 0.045 radians, followed by the MPC controller and the nonlinear integral sliding mode controller. As illustrated in Fig. 5b, using the QP solver and computer with AMD R9 7945HX CPU, the average real-time computation time for the MPC controller is 0.002 seconds, which meets the real-time computation requirements for effective control.

Fig. 5
figure 5

Simulation results of double lane change test for high attached pavement (0.85)

The test on the 0.5 adhesion coefficient road

The simulation results of the double lane change test on a wet road (coefficient of friction = 0.5) are presented in Fig. 6. At this point, the tires remain within the linear region, and the path tracking performance is similar to that observed on conventional road surfaces. The tracking effectiveness of the LQR and MPC controllers is comparable; however, the maximum lateral displacement error for the MPC is significantly smaller. The lateral error of the nonlinear integral sliding-mode controller remains relatively stable, staying within 0.02 m. Nevertheless, as the road surface attachment coefficient decreases, both the center of mass side deflection angle and the actual wheel steering angle exhibit more pronounced changes.

Fig. 6
figure 6

Simulation results of double lane change test on wet road (0.5)

The test on the 0.35 adhesion coefficient road

As road conditions deteriorate, the tires enter a nonlinear region, which significantly tests the performance requirements of the controller. The simulation results of the double lane change test conducted on snow and ice (coefficient of friction = 0.35) are presented in Fig. 7. All three controllers are generally able to follow the reference path; however, the LQR controller demonstrates the best performance, maintaining a maximum heading angle error within 0.05 radians. In contrast, the lateral error of the nonlinear integral sliding mode controller increases noticeably, performing poorly compared to the high and medium adhesion surfaces. The MPC controller exhibits minimal lateral displacement error during the 4–9 s interval. Specifically, during this period, the lateral displacement error of the MPC controller is very small, and the actual turning angle of the wheels is less than that of both the LQR and nonlinear integral sliding mode controllers, indicating a more effective path tracking capability with reduced control inputs. These results suggest that the MPC controller exhibits high robustness under the challenging conditions of the external road environment.

Fig. 7
figure 7

Simulation results of double lane change test on icy road (0.35)

Case B: circular path test

In order to demonstrate the steady-state characteristics of the proposed three lateral controllers on low and medium-adhesion road surfaces, a circular path test condition is selected. The vehicle enters the test road with an initial speed of 54 km/h, the road adhesion coefficient is 0.5, and the radius of the reference path’s circumference is 60 m. The reference path is illustrated in Fig. 8a.

Fig. 8
figure 8

Simulation results of circular path test

The control results for the circumferential path are presented in Fig. 8. In both the middle and low adhesion road surfaces, all three controllers effectively track the reference path. The actual steering angle, centroid side deflection angle, and heading angle errors among the three controllers are relatively similar, with the heading error ultimately stabilizing at − 0.03 radians. Notably, the MPC exhibits the smallest lateral displacement error and converges rapidly to zero, achieving stable tracking. In contrast, the nonlinear integral sliding mode control converges more slowly but ultimately reaches a zero steady-state error. The maximum lateral displacement error for the LQR is − 0.06 m, with a final steady-state error of approximately 0.03 m, which is less favorable compared to the tracking steady-state characteristics of the other controllers.

Step speed tracking test

In order to verify the steady-state tracking performance of the proposed two longitudinal controllers for speed tracking, a step vehicle speed response experiment was conducted. The road surface adhesion coefficient was set at 0.8, the initial front wheel angle was zero, and the initial vehicle speed was also zero. As illustrated in Fig. 9a, the vehicle was accelerated twice before reaching 70 s. The speed increased to 30 km/h at 10 s, and then the vehicle continued to accelerate to 50 km/h by 30 s. After 70 s, the speed decreased to 10 km/h and subsequently maintained a constant speed.

Fig. 9
figure 9

Longitudinal vehicle speed tracking simulation results

The simulation results are shown in Fig. 9. Both longitudinal controllers effectively track the reference speed, with the steady-state speed tracking error approaching zero. The average rise time is approximately 2 s. However, the MPC controller exhibits a jittering effect when the speed changes, which is attributed to constraint issues.

Comprehensive evaluation

Both proposed longitudinal controllers can track the reference speed quickly and accurately, demonstrating good steady-state tracking performance. During the speed tracking process, the PID controller provides a rapid response in both driving and braking modes, making it more suitable for longitudinal speed tracking control due to its relatively intuitive design and ease of parameter tuning. In contrast, the proposed Model Predictive Control (MPC) controller can quickly track the reference speed in driving mode; however, it exhibits a slower braking response due to constraints encountered in braking mode. As shown in Fig. 9b, the MPC controller also suffers from a jitter effect. Generally, the MPC controller has higher requirements for the accuracy of system modeling, making adjustments more challenging and increasing computational complexity. Therefore, when selecting a speed-tracking controller, the simpler and more user-friendly PID controller is often the more appropriate choice.

To facilitate the analysis of the trajectory tracking effectiveness of the three proposed lateral controllers, the root mean square error (RMSE) is included as one of the metrics. The equation is expressed as follows:

$$RMSE = \sqrt {\frac{1}{N}\sum\limits_{i = 1}^{n} {\left( {y_{i} - y_{d} } \right)^{2} } }$$
(70)

Where N denotes the length of the sampling period, yi denotes the measured output, and yd indicates the reference output. The comprehensive performance of the controllers is evaluated by analyzing the maximum lateral displacement error, heading angle error, maximum front wheel turning angle, and the root mean square value of each controller under three different road adhesion coefficient conditions during the double lane change test. The results are presented in Table 2.

Table 2 Quantitative statistics of evaluation indicators.

In order to more intuitively compare the comprehensive performance of the three lateral controllers, each performance indicator is presented under three different adhesion coefficients. At the same time, to enhance the clarity of the graph, the data is displayed with two significant digits, as illustrated in Fig. 10.

Fig. 10
figure 10figure 10

Comparison bar chart of three controllers with different road adhesion coefficients

In terms of the lateral tracking effect, both the maximum lateral displacement error and the root mean square error of the MPC controller decrease as the adhesion coefficient of the road surface declines from 0.85 to 0.5, indicating improved control performance. However, when the adhesion coefficient further decreases to 0.35, both the maximum lateral displacement error and the root mean square error increase. In contrast, the maximum lateral displacement error of the NISMC controller on medium to high adhesion road surfaces is only 0.028 m, with the root mean square error stabilizing within 0.01 m. This demonstrates excellent control performance on good road surfaces. Nevertheless, the control effectiveness significantly diminishes on icy and snowy road surfaces, where the maximum lateral displacement error and root mean square error increase by approximately 0.1 m and 0.03 m, respectively, indicating relatively poor robustness on low-adhesion road surfaces. The maximum lateral error of the LQR controller remains around 0.07 m across the three road conditions, and interestingly, the lateral displacement error decreases as the road surface adhesion coefficient decreases.

In terms of heading tracking performance, the MPC controller and the LQR controller exhibit similar effectiveness, with the maximum heading error and the root mean square error stabilized at approximately 0.06 radians and 0.02 radians, respectively. This level of performance ensures effective heading tracking. In contrast, the NISMC controller demonstrates slightly inferior performance, with its maximum heading error exceeding 0.06 m and the root mean square of the heading error greater than 0.02 radians.

In terms of control inputs, the maximum wheel turning angle of the MPC controller is less than 6 degrees on both medium and low traction surfaces. As the road adhesion coefficient decreases to 0.35, the maximum wheel turning angle increases by only about 1.5°, with a maximum root mean square error of 2.39° on icy and snowy road surfaces. The LQR controller maintains a smaller wheel turning angle on medium and low traction surfaces, and its control inputs are comparable to those of the MPC. However, when the road adhesion coefficient is reduced to 0.35, the control inputs significantly increase to 16.7° and 3.3°, respectively. The NISMC controller does not fully account for the influence of control inputs; to ensure effective tracking, its wheel angle increases as the road surface adhesion coefficient decreases, particularly in poor road conditions, resulting in a maximum wheel angle of 2.39°. The LQR controller can ensure a small wheel angle on medium to low traction road surfaces, with control inputs similar to those of the MPC. Notably, when the road environment deteriorates, the maximum wheel angle and root mean square error reach 22.2° and 4.67°, respectively.

To accurately assess the control potential of the three controllers, six performance indicators were selected to evaluate them under a road adhesion coefficient of 0.35. A lower value indicates better performance, resulting in a higher score. The scoring system operates on a scale from 0 to 10, where 10 represents the best performance and 0 signifies the worst. For each indicator, we will identify the maximum and minimum values among the three controllers and apply the following formula to assign scores:

$$Score = 10 \times \frac{{{\mathbb{R}}_{\min } }}{{{\mathbb{R}}_{value} }}$$
(71)

In this formula, \({\mathbb{R}}_{value}\) indicates the current controller indicator value, and \({\mathbb{R}}_{min}\) refers to the minimum value among the values of the three controllers for this indicator, which is also regarded as the best value.

The index scores of the three controllers obtained through calculation are shown in Table 3.

Table 3 Six-dimensional index rating table.

According to the performance index scores of the three controllers presented in Table 3, a six-dimensional radar chart has been created, as illustrated in Fig. 11. Under extreme adhesion road conditions, the MPC achieved an overall performance score of 9.24 points. It excelled in heading error control and front wheel angle control, demonstrating only a slight disadvantage compared to the LQR in lateral error control. Notably, the MPC’s overall performance improved by 11% and 63% compared to the LQR and NISMC, respectively. The comprehensive performance score for the LQR is 8.32; its primary advantage lies in maintaining stability in lateral error. However, this comes at the cost of excessive front wheel angle output, which may lead to comfort issues such as abrupt steering and potential collisions during actual driving. The NISMC recorded the lowest overall performance score of only 5.66 points, exhibiting poor robustness and immunity to extreme driving conditions, with its performance deteriorating by 87% compared to conventional driving conditions.

Fig. 11
figure 11

Six-dimensional score chart.

In general, the MPC controller can accurately and smoothly track the upper reference trajectory while maintaining small control inputs. It addresses the road’s large curvature or curvature discontinuities through model prediction, rolling optimization, and real-time computation. This approach balances inputs and outputs to achieve optimal control and demonstrates improved robustness. However, the comprehensive consideration of the vehicle dynamics model and constraints increases the complexity of optimization and solution processes. Consequently, this necessitates significant computational capability from the controller, and real-time computation remains a critical factor limiting the application of MPC in motion control. In contrast, the LQR controller is generally less effective than MPC in managing system dynamics and nonlinear issues. Nevertheless, it ensures system stability and can achieve optimal solutions within a fixed time frame. The proposed NISMC controller outperforms both MPC and LQR under normal operating conditions, ensuring rapid and smooth tracking of the reference path. However, when road conditions become severe or when there are sudden changes in curvature, the control effectiveness of NISMC diminishes compared to MPC. Despite this, it still guarantees system stability and can find optimal solutions within a fixed time domain. It is important to note that under adverse road conditions or sudden curvature changes, tracking accuracy may decline due to overshooting caused by the integral term. Additionally, it takes time for the system to recover from a zero steady-state error. In summary, MPC demonstrates the most comprehensive performance and maintains effective control even under extreme conditions, making it suitable for high-precision control scenarios. The lateral control of the LQR is outstanding, but the load capacity of the actuator needs to be optimized. It can also perform well under certain conditions. The control performance of Nonlinear Integral Sliding Mode Control (NISMC) tends to deteriorate significantly as the driving environment worsens, limiting its applicability to certain characteristic scenarios and conventional working conditions.

Conclusion

In this paper, we present a comparative study of three lateral controllers, MPC, LQR, and NISMC as well as two longitudinal controllers, MPC and PID, focusing on trajectory tracking and speed tracking. This study is based on a three-degree-of-freedom vehicle dynamics model and a trajectory-tracking error-based model.

In comparing the lateral controllers, the comprehensive performance of three different lateral controllers is evaluated through two scenarios: a double lane change test, and a circular path test, each conducted on surfaces with varying road adhesion coefficients. Considering the system’s capability to handle multiple constraints, the first lateral controller is designated as the MPC controller, which demonstrates excellent tracking performance and resistance to interference in simulation experiments, yielding the best overall performance. The second lateral controller employs LQR control, which exhibits slightly inferior comprehensive performance compared to the MPC but offers advantages in real-time processing and computational complexity, effectively maintaining control stability during simulations. The third controller introduces a lateral controller that employs sliding mode control based on a nonlinear conditional integrator. Simulation results demonstrate that the NISMC controller outperforms the others in terms of accuracy and response time under both optimal and normal road conditions. At the same time, in order to reflect the control potential of the three controllers, we employed a six-dimensional scoring system for evaluating the controllers’ performance on low-adhesion pavement with a coefficient of 0.35, allowing for a more direct assessment of their overall performance. The results indicated that the MPC achieved the highest comprehensive performance score of 9.24. Furthermore, the MPC’s performance was 11% and 63% superior to that of the LQR and NISMC, respectively. In contrast, the NISMC recorded the lowest comprehensive performance score of only 5.66, which was 87% lower than the performance observed on high-adhesion pavement with a coefficient of 0.85. In the comparison of longitudinal controllers, the steady-state performance of speed tracking between MPC and PID control is evaluated through a step speed tracking test. The simulation results reveal that the PID controller responds quickly to track the reference speed, while the MPC can also follow the vehicle’s speed but exhibits a jitter effect due to tuning parameter constraints and other issues. Therefore, PID control is recommended as the preferred choice for longitudinal speed-tracking controllers.

It is important to note that the control algorithms proposed in this paper have been validated through simulation. In the future, we plan to establish a real-vehicle experimental platform to further evaluate the control methods presented in this study. In addition, we will pay attention to the problem of actuator saturation and consider issues such as active disturbance rejection and parameter observation and estimation in the subsequent research.