Next Article in Journal
Adaptive Fuzzy Command Filtered Tracking Control for Flexible Robotic Arm with Input Dead-Zone
Previous Article in Journal
High-Performance Flux Tracking Controller for Reluctance Actuator
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Enhancing Autonomous Vehicle Lateral Control: A Linear Complementarity Model-Predictive Control Approach

School of Automation and Electrical Engineering, Shenyang Ligong University, Shenyang 110159, China
*
Author to whom correspondence should be addressed.
Appl. Sci. 2023, 13(19), 10809; https://doi.org/10.3390/app131910809
Submission received: 11 September 2023 / Revised: 25 September 2023 / Accepted: 27 September 2023 / Published: 28 September 2023

Abstract

:
Model-predictive control (MPC) offers significant advantages in addressing constraint-related challenges and plays a pivotal role in self-driving car technology. Its primary goal is to achieve precise trajectory tracking while prioritizing vehicle stability and safety. However, real-time operations often face challenges related to computational demands and low computational efficiency. To address these challenges, this paper introduces a novel lateral control algorithm for self-driving vehicles, which utilizes the linear complementarity problem (LCP) instead of the conventional quadratic programming (QP) method as the MPC optimization solution. This innovative approach incorporates the electric steering system into the vehicle dynamics model, allowing for precise torque regulation of the steering motor and enhancing control accuracy. The MPC algorithm adopts the LCP solution method to calculate control signals based on the vehicle’s state, ensuring both rapid and stable vehicle control. Simulation results demonstrate that the proposed MPC algorithm, utilizing the LCP solution method, effectively addresses efficiency issues in the lateral motion of self-driving cars. This leads to improvements in both driving stability and real-time performance. Overall, this innovative approach lays a solid foundation for the practical implementation of self-driving cars.

1. Introduction

Autonomous vehicles (AVs) have revolutionized the transportation sector, offering significant benefits in terms of road safety, reduced congestion, and environmental advantages [1]. However, realizing these advantages necessitates the development of sophisticated control algorithms to ensure consistent and reliable performance across diverse driving conditions. A critical challenge lies in designing a responsive lateral control algorithm that enables AVs to stay within lanes, avoid collisions, and navigate seamlessly, even on challenging roads [2,3].
In recent times, substantial progress has been made in the development of lateral control algorithms for autonomous vehicles, with the ultimate goal of achieving safe road operation without human intervention [4]. Research has explored various aspects of lateral control, including trajectory planning, path following, and obstacle avoidance [5]. Model-based strategies, such as proportional–integral–derivative (PID) control, linear quadratic regulator (LQR) control, and model-predictive control (MPC), utilize feedback mechanisms to fine-tune the vehicle’s steering angle and achieve precise trajectory tracking. Conversely, model-free approaches like reinforcement learning (RL), neural networks, and genetic algorithms leverage data-driven methods to learn optimal control strategies [6].
Coppola et al. [7] introduced a novel and robust distributed PID control method, specifically designed to ensure robust tracking performance for all vehicles within a fleet. However, it is important to note that the effectiveness of PID control hinges on precise parameter tuning. Abajo et al. [8] addressed the challenge of parameter tuning by employing a genetic algorithm (GA) for optimizing PID parameters during trajectory tracking. This approach offers an automated and data-driven method for achieving optimal control performance. In contrast, Li et al. [9] introduced real-time feedforward and feedback LQR control to ensure accurate tracking, vehicle stability, and reliability. This method also integrates real-time path planning and control input parameter optimization, contributing to precise and dynamic control. Lu et al. [10] developed an online adaptive LQR control by optimizing parameters using a novel genetic algorithm fitness function. This approach adapts the control strategy in real time, enhancing its adaptability to changing conditions. Shen et al. [11] proposed a robust H infinity state feedback control (RSC) method that demonstrated superior performance compared to traditional MPC controllers, particularly in lateral vehicle motion scenarios. For agile maneuvers, Zhou et al. [12] applied a Popov–H∞ controller using linear fractional transformation (LFT) to handle nonlinear constraints, enabling effective control during challenging maneuvers. In high-curvature situations, Rinaldi et al. [13] presented a suboptimal sliding mode control scheme that adjusted heading angle and velocity to enhance tracking accuracy, particularly in scenarios with sharp turns. Ding et al. [14] effectively reduced chattering in second-order sliding mode (SOSM) control by integrating improved adding power integrator (API) technology, contributing to smoother control performance. Mohammadzadeh et al. [15] utilized nonstationary fuzzy sets to estimate AV dynamic characteristics and derived adaptive laws for versatile path tracking, enabling robust control in varying conditions. Lakhekar et al. [16] proposed an adaptive mechanism that combines sliding mode control and fuzzy logic, offering efficient path following with adaptability to different dynamics and disturbances. Addressing complex dynamics, Peng et al. [17] introduced a model-based deep reinforcement learning approach to motion control, leveraging deep reinforcement learning techniques to enhance control performance. Lastly, Chen et al. [18] employed two deep reinforcement learning algorithms for controlling the speed, steering angle, and power distribution of the powertrain. This approach achieved stable and effective control outcomes, particularly in complex control scenarios.
MPC stands out as a popular choice for autonomous vehicle lateral control, primarily due to its adeptness in handling constraints [19]. Ge et al. [20] introduced a model-predictive integrated controller employing Bezier curve fitting for lane changing, maintaining tracking accuracy without frequent parameter updates. Zou et al. [21] integrated an event-triggering mechanism, enhancing real-time performance. Cao et al. [22] optimized LTV-MPC for adaptability and robustness, even on challenging paths. To address network attacks, Lian et al. [23] employed a fuzzy system and asynchronous elastic event-triggering mechanism for closed-loop control. Liu et al. [24] optimized momentum using robust MPC for hybrid electric vehicles. For handling uncertainties, Tian et al. [25] utilized MPC and H infinity design, ensuring robustness and accuracy through linear matrix inequalities. While the aforementioned MPC control methods enhance robustness against interference during AV trajectory tracking, they may not fully meet real-time requirements. Mollajafari et al. [26] have made a significant contribution to enhancing the robustness of MPC by developing an adaptive fuzzy MPC that takes into account load variations and time-varying parameters. In addition, to address the computational efficiency challenge of the controller, they have introduced an optimization method called time–cost compromise CPoP, which notably improves the computational efficiency of the controller [27].
All of the aforementioned lateral control methods have prioritized aspects of robustness and computational efficiency in vehicle tracking. However, it is crucial to note that the MPC controller, due to its requirement of solving a constrained optimization problem at each sampling time, can incur a substantial online computational burden, necessitating further optimization efforts. In response to these challenges, this study introduces an MPC framework founded on the linear complementarity problem (LCP) solution method. This novel approach replaces the traditional quadratic programming (QP) method and aims to address both robustness and computational efficiency issues within the existing MPC framework. The primary objective is to enhance the real-time performance and stability of self-driving car controllers.
The key contributions of this study can be summarized as follows:
  • A comprehensive model of the vehicle’s steering system has been developed. This model, combined with a dynamic tire model, enables precise control of the motor torque used to adjust the steering angle. This well-crafted model enhances vehicle control accuracy.
  • By integrating LCP solving techniques, this study enhances the efficiency of solving QP problems within the MPC framework.
  • The vehicle has been experimentally analyzed under two challenging road conditions—high friction and low friction—and compared with PID and conventional QP solution methods. This empirical validation validates the reliability of the proposed algorithm.
This article’s structure is organized into several sections as follows:
Section 2 dives into the modeling of the vehicle system, including discussions on the electric power assist system (Section 2.1), vehicle dynamics, and tire characteristics (Section 2.2), as well as the integration of steering structure and dynamics (Section 2.3). In Section 3, the focus shifts to the design of the controller. This chapter outlines the composition of the controller (Section 3.1), discusses the design of the QP solver (Section 3.2), and introduces the LCP solver (Section 3.3). Additionally, Section 3.4 offers an analysis of the system’s stability, followed by a detailed explanation of the controller’s computation process in Section 3.5. Lastly, in Section 4, this article provides validation of the controller’s effectiveness through a series of simulation experiments. This structured organization allows for a systematic exploration of vehicle system modeling, controller design, and the empirical assessment of the proposed methodology.

2. Steering and Vehicle Systems Modeling

2.1. Dynamic Model of Steering System

To incorporate the steering system model into the vehicle dynamics control framework, only the torque of the steering motor is used as the control input for the vehicle’s steering mechanism [28]. N s represents the motion ratio between the motor reducer and the steering system, whereas N m stands for the motion ratio between the steering knuckle and the steering wheel. Figure 1 provides a summary of the essential system configuration. In this model, all forces are evenly applied to the central pin. The correlation between the two motion ratios is defined as stated in [29].
J e q δ ¨ + B e q δ ˙ + τ d i s + τ f sgn ( δ ˙ ) = N s N m τ m
where the torque of the steering motor is denoted as τ m , while τ f represents the equivalent friction constant of the steering system. In addition, τ d i s refers to the steering resistance torque resulting from the force of the front tires. The equivalent inertia and damping of the steering system with respect to the kingpin are represented by J e q and B e q , respectively, with specific values provided as follows:
J e q = J f w + N m N s 2 J m + N s 2 J c + m r r p 2 B e q = B f w + N m N s 2 B m + N s 2 B c + B r r p 2
where J f w and B f w are the moment of inertia and viscous friction of the front wheel, respectively, J m and B m are the moment of inertia and damping coefficient of the motor, J c and B c are the moment of inertia and damping coefficient of the lower steering column, r p is the radius of the pinion, B r is the rack damping coefficient, and m r is the mass of the rack.
Based on Equation (2), taking the steering wheel angle δ and steering wheel angle rate δ ˙ as the state variables of the steering system, the state equation can be represented as follows:
x ˙ 1 = A 1 x 1 + B 1 τ m + N 1 ω τ y 1 = C 1 x
where
A 1 = 0 1 0 B e q J e q B 1 = 0 N m N s J e q N 1 = 0 1 J e q C 1 = 1 0 ω τ = τ d i s + τ f sign ( δ ˙ )
According to Equation (3), the dynamic relationship between the motor torque τ m and the steering wheel angle δ can be obtained. The steering resistance torque τ d i s and the friction torque τ f are external disturbances of the steering system.

2.2. Dynamic Model of Vehicle Tires

To seamlessly integrate the vehicle dynamics framework with the steering system, a 2-DOF vehicle bicycle model is employed to elucidate the lateral dynamics during the path following process. The simplified structure is depicted in Figure 2. Assuming small angles for δ , specifically cos δ 1 and sin δ δ , the longitudinal velocity v x is considered constant, and the lateral acceleration v ˙ y and yaw acceleration φ ¨ of the 2-DOF vehicle are expressed as follows:
v ˙ y = F y f α f m + F y r α r m v x φ ˙ φ ¨ = a F y f α f I z b F y r ( α ) I z
where m is the mass of the vehicle, β is the sideslip angle of the center of mass of the vehicle, I z is the moment of inertia of the vehicle, and v x and v y are the longitudinal velocity and lateral velocity of the vehicle, respectively. F y f and F y r are the lateral forces of the front and rear tires, respectively, and α f and α r are the lateral slip angles of the front and rear tires, respectively, expressed as
α f = v y + a φ ˙ v x δ α r = v y b φ ˙ v x
where the distances from the center of the front and rear axles of the wheel to the center of the body are denoted as a and b, respectively.
In order to clarify the impact of tire models on vehicle dynamics, handling stability, braking safety, and ride comfort, this study uses the Fiala tire model to capture the nonlinear features of automotive tires [30]:
F y = μ s F z 1 1 C α tan α s 3 μ s F z 3 sgn α s , α s < α s l μ s F z sgn α s , α s < α s l
where F y represents the lateral force on the tire, α s is the tire slip angle, C α is the cornering stiffness, α s l = arctan 3 μ s F z C α , F z represents the vehicle vertical force, and μ s is the road friction coefficient.
As shown in Figure 3, to simplify the nonlinear characteristics of tires and reduce computational complexity, the nonlinear tire lateral force is approximated as a linearized function near the working point α f and α r of the Fiala tire model curve. Specifically, this approximation is expressed as follows:
F y f α f = F y f 0 + C f 0 α f α f 0 F y r α r = F y r 0 + C r 0 α r α r 0
where F y f 0 denotes the lateral force of the front wheel at the starting point and F y r 0 denotes the lateral force of the rear wheel at the starting point. Additionally, C f 0 and C r 0 denote the slope of the Fiala tire model at α f 0 and α r 0 , respectively.
To characterize the vehicle’s real trajectory, the lateral position of the vehicle and the yaw angle of the vehicle, measured on a fixed ground axis, are combined into the state vector x 2 = Y , v y , φ , φ ˙ T , and the vehicle dynamics system can be represented as follows:
x ˙ 2 = A 2 x 2 + B 2 δ + N 2 ζ s T y 2 = C 2 x 2
where
A 2 = 0 1 v x 0 0 C f 0 + C r 0 m v x 0 a C f 0 b C r 0 m v x 0 0 0 1 0 a C f 0 b C r 0 I z v x 0 a 2 C f 0 + b 2 C r 0 I z v x
B 2 = 0 C f 0 m 0 a C f 0 I z T
N 2 = 0 1 0 0 0 0 0 1 T C 2 = 1 0 0 0 0 0 1 0
y 2 = Y φ ζ s T = F y f 0 + F y r 0 C f 0 C r 0 α r 0 m a F y f 0 b F y r 0 a C f 0 α f 0 + b C r 0 α r 0 m
Equation (9) establishes a dynamic and time-varying relationship between the steering angle input and the vehicle motion output.

2.3. Steering System and Tire Combination Model

The integration of the steering system (3) and the vehicle dynamics system (9) into a unified model is essential for regulating the vehicle’s lateral motion. The resulting sixth-order dynamic model is represented as follows:
x ˙ = A x + B τ m + N ζ y = C x
where x = δ δ ˙ Y v y φ φ ˙ T , y = Y φ T ,   ζ = ω τ ζ s T , C = 0 2 × 2 C 2 ,
A = A 1 0 2 × 4 B 2 C 1 A 2 B = B 1 0 4 × 1 N = N 1 0 2 × 2 0 4 × 1 N 2
In crafting the controller, the continuous-time system as described in Formula (9) is discretized with a sampling interval of T s , yielding the ensuing discrete-time system:
x ( k + 1 ) = A d x ( k ) + B d τ m ( k ) + N d ζ ( k )
where x ( k ) R 6 , τ m ( k ) R , A d = T s A + I 6 , B d = T s B , and N d = T s N . The integrated system enables the vehicle to track the desired path by regulating the motor’s steering torque, with the steering angle δ serving as a state variable. The variable ζ ( k ) is computed based on the vehicle’s motion state.

3. Fast-MPC Algorithm Establishment

3.1. MPC Controller Design

In the AV tracking process, to address situations where the problem cannot be solved, one can employ the soft constraint method to relax the conditions within the cost function. This approach helps ensure the overall stability of the operation, and the cost function can be expressed as follows:
J ( k ) = i = 1 N p x ( k + i k ) x r e f ( k + i k ) Q 2 + i = 0 N c 1 τ n ( k + i k ) R 2 + κ ε ( k ) 2
such that
δ min δ δ max β min β β max φ ˙ min φ ˙ φ ˙ max τ n min τ n ( k ) τ n max
The cost function integrates vital elements: state weight matrix Q, input weight matrix R, prediction time horizon N p , control time horizon N c , relaxation factor ε , and weighting coefficient κ . Also, a quadratic penalty term involving τ n enhances control optimality and minimizes energy usage. The literature [28] displays the state constraints for vehicle dynamics.

3.2. QP Solver

For tackling the constrained optimization conundrum posed by the nominal predictive controller at each time instance, we introduce the vector U ( k ) R n u N c and determine the optimal control sequence through the utilization of a QP solver. This entails a particular manipulation of the objective function presented in Equation (12).
J ( k ) = min U ( k ) X o ( k ) X r e f ( k ) Q 2 + U ( k ) R 2 + κ ε ( k ) 2
where
X o ( k ) = A ¯ x ( k ) + B ¯ U ( k ) + N ¯ ζ ¯ ( k )
X r e f = x r e f ( k + 1 ) , x r e f ( k + 2 ) , , x r e f k + N p T
with
A ¯ = A d T A d 2 T A d N c T A d N p T T
B ¯ = B d 0 6 × 1 0 6 × 1 0 6 × 1 A d B d B d 0 6 × 1 0 6 × 1 A d N c 1 B d A d N c 2 B d B d A d N p 1 B d A d N c 2 B d A d N p N c B d
N ¯ = N d 0 6 × 3 0 6 × 3 0 6 × 3 A d N d N d 0 6 × 3 0 6 × 3 A d N p 1 N d A d N p 2 N d N d A d N p 1 N d A d N p 2 N d A d N p N c N d
ζ ¯ ( k ) = ζ ( k ) T , ζ ( k + 1 ) T , , ζ k + N c T T
By removing some constant terms, the objective function (14) can be transformed into the following form:
J ( k ) = 1 2 U ( k ) ε ( k ) T H U ( k ) ε ( k ) + U ( k ) ε ( k ) T F x ¯ ( k )
where
x ¯ ( k ) = A ¯ x ( k ) + N ¯ ζ ¯ ( k ) X r e f ( k ) H = 2 B ¯ T Q ¯ B ¯ + R 0 n u N c × 1 0 1 × n u N c 2 κ F = B ¯ T Q ¯ 0 Q ¯ = diag { Q , , Q } R ¯ = diag { R , , R }
We express the constraint form of the optimization problem (17) as
A ˜ x ¯ ( k ) + B ˜ U ( k ) X u l
where
A ˜ = C ¯ A C ¯ A , B ˜ = C ¯ B B ¯ C ¯ B B ¯ , X u l = X u X l
C ¯ A = I N p 1 0 0 0 0 0 0 0 0 1 v x 0 0 0 0 0 0 0 1 0 0 0 0 0 0 C ¯ B = I N p 1 0 0 0 0 0 0 0 0 1 v x 0 0 0 0 0 0 0 1 0 J e q N m N s 0 0 0 0
X ¯ u = δ max β max φ ˙ max τ n max X ¯ l = δ min β min φ ˙ min τ n min X u = X ¯ u , X ¯ u , , X ¯ u T X l = X ¯ l , X ¯ l , , X ¯ l T
The vectors X l and X u contain the minimum and maximum values of the state quantity and control quantity constraints, respectively. The Kronecker product is denoted by the symbol ⊗. The matrices A ˜ and B ˜ are obtained through selecting the appropriate rows from the matrices A ¯ and B ¯ , respectively, in order to represent the state and input constraints.
Ultimately, the MPC problem is transformed into a QP problem that can be solved using a standard QP solver. The QP problem can be formulated as follows:
min J ( k ) = 1 2 U ( k ) ε ( k ) T H U ( k ) ε ( k ) + U ( k ) ε ( k ) T F x ¯ ( k ) s . t . B ˜ U ( k ) X u l A ˜ x ¯ ( k )
Solving the control sequence at the current moment is as follows:
U * ( k ) = arg min J ( k ) = τ n * ( k ) , τ n * ( k + 1 ) , , τ n * k + N c 1 T

3.3. LCP Solver

We transform the constrained quadratic optimization problem of MPC into an equivalent linear complementarity problem. The specific solution steps and proof process of LCPs can be found in the literature [31]. We define the following:
M = B ˜ H 1 B ˜ T Γ = X u l A ˜ x ¯ ( k ) + B ˜ H 1 F x ¯ ( k )
where H is nonsingular. Meanwhile, M is symmetric and either positive or semipositive definite, based on constraints and B ˜ row rank. Denoting the Lagrange multiplier vector as Υ and non-negative slack variable vector as Z, the QP problem’s first-order optimality condition is represented as an LCP:
Find Υ , Z such that Z = M Υ + Γ , Υ T Z = 0 , Z 0 , Υ 0 .
As the LCP is the dual of the corresponding QP problem, its computational load depends only on the number of inequality constraints. It is important to note that converting to an LCP can, in the worst case, double the number of optimization variables. Let Υ * be the solution of the LCP problem. Then, the optimal solution U * ( k ) of the QP problem can be expressed as
U * ( k ) = H 1 F x ¯ ( k ) H 1 B ˜ T Υ *
Within this section, the LCP associated with matrices M and Γ is denoted as LCP ( M , Γ ) . Utilizing the LCP methodology outlined earlier to solve the control law in the context of the MPC problem offers a tangible enhancement in the efficiency of QP solution times. The comprehensive approach and feasibility considerations are meticulously expounded in the referenced article [31].

3.4. Stability Analysis of MPC

Theorem 1.
Considering system (11) along with the cost function (12) and the presence of soft constraints, as well as utilizing positive semidefinite matrix Q and positive definite matrix R, let us denote the optimal cost function at time k, denoted as J ( k ) , as V ( k ) . This leads to the relationship V ( k ) V ( k + 1 ) at time k + 1 , signifying that the optimal solution ensures the stability of system (11).
Proof. 
The Lyapunov function is defined as
V * ( k ) = min J ( k ) = min i = 1 N p x ( k + i k ) x r e f ( k + i k ) Q 2 + i = 0 N c 1 τ m ( k + i k ) R 2 + κ ε ( k ) 2
At times k and k + 1 , the expression for the system input is given by
τ m ( k + 1 + i k + 1 ) = [ τ m ( k + 1 k + 1 ) , τ m ( k + 2 k + 1 ) , τ m k + N c k + 1 = [ τ m * ( k + 1 k ) , τ m * ( k + 2 k ) , τ m * k + N c k ε ( k + 1 ) = ε * ( k )
Based on the predicted performance index of the system at time k, we can establish the relationship between J ( k + 1 ) and V * ( k ) , as shown in (26) below:
J ( k + 1 ) = i = 1 N p x ( k + 1 + i k + 1 ) x r e f ( k + 1 + i k + 1 ) Q 2 + i = 0 N c 1 τ m ( k + 1 + i k + 1 ) R 2 + κ ε ( k + 1 + i k + 1 ) 2 = i = 2 N p x * ( k + i k ) x r e f ( k + i k ) Q 2 + i = 1 N c 1 τ m * ( k + i k ) R 2 + κ ε * ( k + i k ) 2 = i = 1 N p x * ( k + i k ) x r e f ( k + i k ) Q 2 + i = 0 N c 1 τ m * ( k + i k ) R 2 + κ ε * ( k + i k ) 2 x * ( k + 1 k ) x r e f ( k + 1 k ) Q 2 τ m * ( k k ) R 2 κ ε ( k k ) 2 = V * ( k ) x * ( k + 1 k ) x r e f ( k + 1 k ) Q 2 τ m * ( k k ) R 2 κ ε * ( k k ) 2
From the properties of the optimal solution, it is evident that any solution at time k + 1 is not less than the optimal solution V ( k + 1 ) , which can be expressed as V ( k + 1 ) J ( k + 1 ) .
V * ( k + 1 ) J ( k + 1 ) V * ( k ) x * ( k + 1 k ) x r e f ( k + 1 k ) Q 2 τ m * ( k ) R 2 κ ε * ( k ) 2
Finally, we can conclude that V ( k + 1 ) V ( k ) , which establishes the stability of the system.    □

3.5. Fast-MPC Algorithm Process

The paper presents the Fast-MPC control method based on the LCP solver, as illustrated in Figure 4. The steps involved in the control process are presented in Algorithm 1.
Algorithm 1: Fast-MPC Algorithm
1. Initialize the system state and establish the actual vehicle system equation x ( k ) , under the influence of disturbances ω τ ( k ) .
2. For each time step k:
3. Partition the actual system state into the system state x ( k ) .
4. Obtain the nominal system state x ( k ) through the LCP solution, resulting in the control law U * ( k ) = H 1 F x ¯ ( k ) H 1 B ˜ T Υ * by solving for J ( k ) .
5. Employ the nominal control law τ m * ( k ) .
7. Move to the next time step k + 1 .

4. Simulation Analysis

To verify the effectiveness of the LCP-based MPC algorithm proposed in this article, a joint simulation was conducted on the automotive simulation platform Carsim2019/Simulink2019 to verify the path tracking effect. The operating system is Windows 10. It connects modules in Simulink, and the MPC vehicle lateral controller written by Matlab2019 calculates the front wheel angle. After sending it to Carsim, it outputs the current status of the vehicle body, including longitudinal position, lateral position, yaw angle, vehicle speed, and front wheel angle.
In order to assess the stable control of the proposed algorithm, at a speed of 15 m/s, we compare the performance of two solvers, LCP and QP, as well as the classical method, PID, under two different road friction coefficients, μ s = 1 and μ s = 0.4 . The vehicle system parameters are presented in Table 1. We evaluate the performance of the algorithm using the following parameters. The controller parameters for this study are as follows: T s = 0.02 , Q = d i a g { 50 , 50 , 80 , 80 , 100 , 100 } , R = 50 , N p = 15 , N c = 5 , and κ = 1000 .

4.1. High Coefficient of Friction Road Test ( μ s = 1 )

Firstly, to evaluate the durability of the fused integrated model of steering structure tires introduced in this study, a thorough comparison was conducted with the existing classical kinematic [22] and dynamic models [32] found in literature. The results of the experiment conducted on surfaces with high coefficients of friction, demonstrated in Figure 5, suggest that the model proposed in this paper achieves superior control accuracy and efficiently handles the effects of road friction.
The relatively high friction between the tires and the road can provide efficient traction and control for a vehicle traveling over bumpy roads. However, the same rough roads that allow for this improved traction can also cause vibrations that may interfere with the accuracy of track-tracking systems. The intended reference path is designed as follows:
Y r e f = 1.85 [ tanh ( 0.096 X r e f 3.81 ) tanh ( 0.109 X r e f 7.37 ) ]
Figure 6 illustrates a comparative analysis of the tracking performance of the Fast-MPC method and the PID algorithm presented in this research. All three techniques are capable of tracking the desired trajectory on a flat road surface in standard road conditions. However, the controller utilizing the LCP solver demonstrates quicker convergence during operation. Compared to the conventional QP strategy, our proposed method improves speed while achieving greater tracking accuracy, as demonstrated in Table 2 and Figure 7.
In Figure 8 and Figure 9, we observe the variation in the vehicle’s input torque and front wheel angle during trajectory tracking. The use of the conventional PID method results in the highest torque consumption and the greatest change in wheel angle. Conversely, employing LCP and QP consumes the least amount of torque and produces the most stable variation in front wheel angle, making it the most reliable and stable method for trajectory tracking.
Figure 10 and Figure 11 depict the trends of the center-of-mass sideslip angle and yaw rate during vehicle tracking. It can be seen that the LCP solver has smoother variations in sideslip angle and yaw rate and ensures the reliability of the LCP solution.
Real-time computational efficiency is crucial for the operation of self-driving cars. As shown in Figure 12 and Figure 13, this paper transforms the QP problem of an MPC controller into an LCP solution. The computation time is reduced while ensuring accuracy. This meets the needs of real-time driving. The MPC scheme with an LCP solution significantly speeds up computation and improves real-time lateral control, path tracking convergence, and overall vehicle robustness.

4.2. Low Coefficient of Friction Road Test ( μ s = 0.4 )

Figure 14 illustrates a comparison of the models on a low-friction road surface. It is evident that the model outlined in this paper demonstrates consistent control performance on skid-prone road surfaces, thereby improving vehicle control.
Driving on low-friction surfaces reduces the available traction of the vehicle, posing a greater challenge to maintaining vehicle control than on level surfaces. Consequently, such conditions can result in reduced acceleration, longer braking distances, and increased sideslip.
Figure 15 illustrates the impact of reduced road adhesion on vehicle tracking. The interference caused by low friction disrupts PID tracking, leading to errors and instability. Conversely, the LCP and QP solvers continue to guarantee precise tracking, with the fastness of the LCP ensuring accurate and stable tracking even under low adhesion conditions. Detailed error data can be found in Table 3 and Figure 16.
Figure 17 shows the torque input to the vehicle on a low-friction road surface in Figure 16. The LCP approach shows a faster rate of torque change, which facilitates a quick response to disturbances and improves safety and tracking accuracy. Similarly, Figure 18 shows that the LCP achieves more stable front wheel angle changes.
Figure 19 and Figure 20 depict the variation in the vehicle’s side inclination and yaw angle. The LCP method ensures that the variation in these two angles is consistent and controllable and is characterized by moderate amplitude variations. This will ensure smooth and safe vehicle operation.
Figure 21 depicts the computation time of the solver for various parameters. As demonstrated in Figure 22, employing the LCP solution instead of the QP solution results in a significant reduction in controller computational time. This enhanced computational efficiency does not compromise tracking performance but, instead, accelerates the convergence of path tracking and enhances vehicle robustness.
In conclusion, based on the analysis of the two road test cases discussed above, it is evident that employing LCP solvers to solve the MPC optimization problem offers clear advantages. This approach ensures computational efficiency and enhances real-time performance while preserving tracking accuracy. The algorithm’s feasibility has been theoretically substantiated. Nevertheless, it is crucial to acknowledge that the simulation study inherently relies on ideal assumptions. The real-life operation of self-driving cars introduces a host of additional physical factors that may exert computational pressure on the controller. Therefore, further investigation into the practical feasibility of the controller in real-world scenarios is warranted for a comprehensive understanding of its capabilities.

5. Conclusions

In this paper, we present a novel dynamic lateral control strategy for vehicles which utilizes MPC in conjunction with LCP solvers. This strategy enables precise control of the steering motor by integrating the steering system with the dynamic tire characteristics of the vehicle. The tailored MPC controller ensures vehicle stability by adhering to constraints related to sideslip, traverse angular velocity, steering angle, and torque during path tracking. The LCP solver optimizes the MPC computation to provide an efficient and uncompromised performance. Simulation results unequivocally demonstrate that the proposed controller surpasses conventional QP solvers in terms of accuracy, dynamic stability, and real-time performance. This breakthrough is expected to significantly enhance the effectiveness and reliability of self-driving cars, promoting efficient and dependable autonomous driving. However, future research must consider real-world scenarios. It is crucial to test self-driving cars under various conditions, such as wet roads, strong winds, and snowy weather, and to explore control performance at different vehicle speeds. Additionally, upcoming research should delve into topics such as control accuracy and system latency compared to alternative solution approaches.

Author Contributions

Y.D. obtained the funding and supervised the technical research and direction. N.Y. and D.W. carried out the concepts and the method. D.W. designed the experiment and analyzed the data and wrote the original manuscript. N.Y. reviewed and revised the paper. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the Scientific Research Fund of Liaoning Provincial Education Department (grant no.: LJKMZ20220616) and Scientific Research Fund of Liaoning Provincial Education Department: LJKMZ2023.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data used to support the findings of this study are available from the corresponding author upon request.

Acknowledgments

The authors would like to thank the editor and reviewers for providing valuable review comments.

Conflicts of Interest

The authors declare no conflict of interest.

Nomenclature

Mathematical Symbols
R The set of real numbers
0 n × n Zero matrix of n × n
I n The identity matrix of dimension n
Kronecker product
n χ The dimension of state variable
n u The dimension of control variable
Vehicle Parameters
N s / N m Motion ratio
J m / B m Moment of inertia/Damping coefficient of the motor
τ m Steering motor torque
τ f Equivalent friction constant
τ d i s Steering resistance torque
J f w / B f w Inertia/friction of front wheel
J c / B c Inertia/damping of lower steering column
J e q / B e q Equivalent inertia/damping of the steering system
r p Radius of the pinion
B r Rack damping coefficient
m r Rack mass
mVehicle mass
δ / δ ˙ Steering wheel angle/angle rate
F y Tire lateral force
β Sideslip angle
α s Tire slip angle
C α Cornering stiffness
F z Vehicle vertical force
μ s Road friction coefficient
I z Moment of inertia of the vehicle
v x / v y Longitudinal/lateral velocity of the vehicle
F y f / F y r Lateral forces of the front/rear tires
α f / α r Lateral slip angles of the front/rear tires
φ Heading angle

References

  1. Hu, X.; Zheng, Z.; Chen, D.; Sun, J. Autonomous vehicle’s impact on traffic: Empirical evidence from Waymo Open Dataset and implications from modelling. IEEE Trans. Intell. Transp. Syst. 2023, 24, 6711–6724. [Google Scholar] [CrossRef]
  2. Araghi, F.M.; Rabinwoitz, A.; Ang, C.C.; Sharma, S.; Kadav, P.; Meyer, R.T.; Bradley, T.; Asher, Z.D. Identifying and assessing research gaps for energy efficient control of electrified autonomous vehicle Eco-Driving. In Machine Learning and Optimization Techniques for Automotive Cyber-Physical Systems; Springer: Cham, Switzerland, 2023; pp. 759–786. [Google Scholar]
  3. Óscar, S.G.; Rubén, C.P.; Esther, G.G.M.; Soledad, N.L. Environmental impacts of autonomous vehicles: A review of the scientific literature. Sci. Total Environ. 2022, 830, 154615. [Google Scholar]
  4. Cao, D.; Wang, X.; Li, L.; Lv, C.; Na, X.; Xing, Y.; Li, X.; Li, Y.; Chen, Y.; Wang, F.Y. Future directions of intelligent vehicles: Potentials, possibilities, and perspectives. IEEE Trans. Intell. Veh. 2022, 7, 7–10. [Google Scholar] [CrossRef]
  5. Bai, Y.; Zhang, B.; Xu, N.; Zhou, J.; Shi, J.; Diao, Z. Vision-based navigation and guidance for agricultural autonomous vehicles and robots: A review. Comput. Electron. Agric. 2023, 205, 107584. [Google Scholar] [CrossRef]
  6. Taghavifar, H.; Shojaei, K. Adaptive robust control algorithm for enhanced path-tracking performance of automated driving in critical scenarios. Soft Comput. 2023, 27, 8841–8854. [Google Scholar] [CrossRef]
  7. Coppola, A.; Lui, D.G.; Petrillo, A.; Santini, S. Cooperative driving of heterogeneous uncertain nonlinear connected and autonomous vehicles via distributed switching robust PID-like control. Inf. Sci. 2023, 625, 277–298. [Google Scholar] [CrossRef]
  8. Rico, A.M.; Enrique, S.G.J.; Matilde, S. Evolutive tuning optimization of a pid controller for autonomous path-following robot. In Proceedings of the 16th International Conference on Soft Computing Models in Industrial and Environmental Applications (SOCO 2021), Bilbao, Spain, 22–24 September 2021; Springer: Berlin/Heidelberg, Germany, 2022; pp. 451–460. [Google Scholar]
  9. Li, H.; Peiqing, L.; Likang, Y.; Jun, Z.; Qipeng, L. Safety research on stabilization of autonomous vehicles based on improved-LQR control. AIP Adv. 2022, 12, 015313. [Google Scholar] [CrossRef]
  10. Ao, L.; Ziwang, L.; Runfeng, L.; Guangyu, T. Adaptive LQR Path Tracking Control for 4WS Electric Vehicles Based on Genetic Algorithm. In Proceedings of the 2022 6th CAA International Conference on Vehicular Control and Intelligence (CVCI), Nanjing, China, 28–30 October 2022; pp. 1–6. [Google Scholar]
  11. Zhikang, S.; Yuquan, D.; Wei, G.; Wentao, H.; Xiaochao, L.; Haiyan, C.; Fenjun, L.; Wenya, L.; Adrian, G. Refill friction stir spot welding Al alloy to copper via pure metallurgical joining mechanism. Chin. J. Mech. Eng. 2021, 34, 75. [Google Scholar]
  12. Zhou, X.; Wang, Z.; Wang, J. Popov-H robust path-tracking control of autonomous ground vehicles with consideration of sector-bounded kinematic nonlinearity. J. Dyn. Syst. Meas. Control 2021, 143, 111004. [Google Scholar] [CrossRef]
  13. Rinaldi, G.; Menon, P.P.; Edwards, C. Suboptimal Sliding Mode-based Heading and Speed Guidance Scheme for Boundary Tracking with Autonomous Vehicle. In Proceedings of the 2021 American Control Conference (ACC), New Orleans, LA, USA, 25–28 May 2021; pp. 1–6. [Google Scholar]
  14. Chen, D.; Shihong, D.; Xinhua, W.; Keqi, M. Output feedback sliding mode control for path-tracking of autonomous agricultural vehicles. Nonlinear Dyn. 2022, 110, 2429–2445. [Google Scholar]
  15. Ardashir, M.; Hamid, T. A robust fuzzy control approach for path-following control of autonomous vehicles. Soft Comput. 2020, 24, 3223–3235. [Google Scholar]
  16. Lakhekar, G.V.; Waghmare, L.M. Robust self-organising fuzzy sliding mode-based path-following control for autonomous underwater vehicles. J. Mar. Eng. Technol. 2022, 22, 131–152. [Google Scholar] [CrossRef]
  17. Peng, Z.; Liu, E.; Pan, C.; Wang, H.; Wang, D.; Liu, L. Model-based deep reinforcement learning for data-driven motion control of an under-actuated unmanned surface vehicle: Path following and trajectory tracking. J. Frankl. Inst. 2023, 360, 4399–4426. [Google Scholar] [CrossRef]
  18. Chen, J.; Li, S.; Yang, K.; Wei, C.; Tang, X. Deep Reinforcement Learning-based Integrated Control of Hybrid Electric Vehicles Driven by Lane-Level High Definition Map. IEEE Trans. Transp. Electrif. 2023. [Google Scholar] [CrossRef]
  19. Hui, S.; Dayi, Q.; Haibing, G.; Kekun, Z.; Tao, W. Lane-Changing Trajectory Tracking and Simulation of Autonomous Vehicles Based on Model Predictive Control. Sustainability 2022, 14, 13272. [Google Scholar]
  20. Linhe, G.; Yang, Z.; Fangwu, M.; Konghui, G. Towards longitudinal and lateral coupling control of autonomous vehicles using offset free MPC. Control Eng. Pract. 2022, 121, 105074. [Google Scholar]
  21. Kai, Z.; Yingfeng, C.; Long, C.; Xiaoqiang, S. Event-triggered nonlinear model predictive control for trajectory tracking of unmanned vehicles. Proc. Inst. Mech. Eng. Part D J. Automob. Eng. 2021, 237, 2474–2483. [Google Scholar]
  22. Jingwei, C.; Chuanxue, S.; Silun, P.; Shixin, S.; Xu, Z.; Feng, X. Trajectory tracking control algorithm for autonomous vehicle considering cornering characteristics. IEEE Access 2020, 8, 59470–59484. [Google Scholar]
  23. Zhi, L.; Peng, S.; Cheng-Chew, L.; Xin, Y. Fuzzy-model-based lateral control for networked autonomous vehicle systems under hybrid cyber-attacks. IEEE Trans. Cybern. 2022, 53, 2600–2609. [Google Scholar]
  24. Baoshuai, L.; Hui, L.; Ziyong, H.; Yechen, Q.; Lijin, H.; Xiaolei, R. Motion control framework for unmanned wheel-legged hybrid vehicle considering uncertain disturbances based robust model predictive control. J. Vib. Control 2023. [Google Scholar] [CrossRef]
  25. Ying, T.; Qiangqiang, Y.; Peng, H.; Shengyuan, W. A Gain-Scheduled Robust Controller for Autonomous Vehicles Path Tracking Based on LPV System with MPC and H. IEEE Trans. Veh. Technol. 2022, 71, 9350–9362. [Google Scholar]
  26. Mollajafari, M.; Shojaeefard, M.H. TC3PoP: A time-cost compromised workflow scheduling heuristic customized for cloud environments. Clust. Comput. 2021, 24, 2639–2656. [Google Scholar] [CrossRef]
  27. Negahban, M.; Ardalani, M.V.; Mollajafari, M.; Akbari, E.; Talebi, M.; Pouresmaeil, E. A novel control strategy based on an adaptive fuzzy model predictive control for frequency regulation of a microgrid with Uncertain and time-varying parameters. IEEE Access 2022, 10, 57514–57524. [Google Scholar] [CrossRef]
  28. Yang, K.; Liu, Y.; Liu, Y.; He, X.; Ji, X. A linear time-varying MPC method for vehicle path-following assistance based on steering torque. In Proceedings of the IECON 2017—43rd Annual Conference of the IEEE Industrial Electronics Society, Beijing, China, 29 October–1 November 2017; pp. 4559–4564. [Google Scholar]
  29. Wang, H.; Kong, H.; Man, Z.; Cao, Z.; Shen, W. Sliding mode control for steer-by-wire systems with AC motors in road vehicles. IEEE Trans. Ind. Electron. 2013, 61, 1596–1611. [Google Scholar] [CrossRef]
  30. Leanza, A.; Mantriota, G.; Reina, G. On the vehicle dynamics prediction via model-based observation. Veh. Syst. Dyn. 2023, 1–22. [Google Scholar] [CrossRef]
  31. Okawa, I.; Nonaka, K. Linear complementarity model predictive control with limited iterations for box-constrained problems. Automatica 2021, 125, 109429. [Google Scholar] [CrossRef]
  32. Gao, H.; Kan, Z.; Li, K. Robust lateral trajectory following control of unmanned vehicle based on model predictive control. IEEE ASME Trans. Mechatron. 2021, 27, 1278–1287. [Google Scholar] [CrossRef]
Figure 1. Vehicle steering system architecture.
Figure 1. Vehicle steering system architecture.
Applsci 13 10809 g001
Figure 2. Vehicle dynamics model.
Figure 2. Vehicle dynamics model.
Applsci 13 10809 g002
Figure 3. Fiala lateral force.
Figure 3. Fiala lateral force.
Applsci 13 10809 g003
Figure 4. The control flowchart.
Figure 4. The control flowchart.
Applsci 13 10809 g004
Figure 5. Model comparison ( μ s = 1 ).
Figure 5. Model comparison ( μ s = 1 ).
Applsci 13 10809 g005
Figure 6. The path tracking effect ( μ s = 1 ).
Figure 6. The path tracking effect ( μ s = 1 ).
Applsci 13 10809 g006
Figure 7. Tracking error statistics ( μ s = 1 ).
Figure 7. Tracking error statistics ( μ s = 1 ).
Applsci 13 10809 g007
Figure 8. The torque ( μ s = 1 ).
Figure 8. The torque ( μ s = 1 ).
Applsci 13 10809 g008
Figure 9. The front wheel angle ( μ s = 1 ).
Figure 9. The front wheel angle ( μ s = 1 ).
Applsci 13 10809 g009
Figure 10. The sideslip angle ( μ s = 1 ).
Figure 10. The sideslip angle ( μ s = 1 ).
Applsci 13 10809 g010
Figure 11. The yaw rate ( μ s = 1 ).
Figure 11. The yaw rate ( μ s = 1 ).
Applsci 13 10809 g011
Figure 12. The performance with respect to horizon ( μ s = 1 ).
Figure 12. The performance with respect to horizon ( μ s = 1 ).
Applsci 13 10809 g012
Figure 13. Runtime ( μ s = 1 ).
Figure 13. Runtime ( μ s = 1 ).
Applsci 13 10809 g013
Figure 14. Model comparison ( μ s = 0.4 ).
Figure 14. Model comparison ( μ s = 0.4 ).
Applsci 13 10809 g014
Figure 15. The path tracking effect ( μ s = 0.4 ).
Figure 15. The path tracking effect ( μ s = 0.4 ).
Applsci 13 10809 g015
Figure 16. Tracking error statistics ( μ s = 0.4 ).
Figure 16. Tracking error statistics ( μ s = 0.4 ).
Applsci 13 10809 g016
Figure 17. The torque ( μ s = 0.4 ).
Figure 17. The torque ( μ s = 0.4 ).
Applsci 13 10809 g017
Figure 18. The front wheel angle ( μ s = 0.4 ).
Figure 18. The front wheel angle ( μ s = 0.4 ).
Applsci 13 10809 g018
Figure 19. The sideslip angle ( μ s = 0.4 ).
Figure 19. The sideslip angle ( μ s = 0.4 ).
Applsci 13 10809 g019
Figure 20. The yaw rate ( μ s = 0.4 ).
Figure 20. The yaw rate ( μ s = 0.4 ).
Applsci 13 10809 g020
Figure 21. The performance with respect to horizon ( μ s = 0.4 ).
Figure 21. The performance with respect to horizon ( μ s = 0.4 ).
Applsci 13 10809 g021
Figure 22. Runtime ( μ s = 0.4 ).
Figure 22. Runtime ( μ s = 0.4 ).
Applsci 13 10809 g022
Table 1. Vehicle system parameters.
Table 1. Vehicle system parameters.
ParametersDefinitionValue
mVehicle mass1370 kg
aHorizontal distance from center of gravity to front tire 1.22 m
bHorizontal distance from center of gravity to rear tire 1.21 m
I z Yaw inertia2125 kg · m 2
C f 0 Front tire turning stiffness62,108 Nm/rad
C r 0 Rear tire turning stiffness46,505 Nm/rad
J f w Moment of inertia of the front wheels 2.8 kg · m 2
B f w Viscous friction of front wheels13Nm · s/rad
J m Moment of inertia of motor 0.0025 kg · m 2
B m Motor damping coefficient 0.032 Nm · s/rad
J c Moment of inertia of lower steering column 0.03 kg · m 2
B c Lower steering column damping coefficient 0.06 Nm · s/rad
B r Rack damping coefficient 7.5 N · s/m
m r Rack quality 1.820 kg
r p Pinion radius 0.0065 m
Table 2. Tracking error ( μ s = 1 ).
Table 2. Tracking error ( μ s = 1 ).
Tracking Error
MethodAverageMaxMinMSE
MPC (LCP)3.6%0.381−0.2210.148
MPC (QP)4.7%0.564−0.3160.153
PID6.6%0.861−0.5230.311
Table 3. Tracking error ( μ s = 0.4 ).
Table 3. Tracking error ( μ s = 0.4 ).
Tracking Error
MethodAverageMaxMinMSE
MPC (LCP)3.1%0.387−0.2420.153
MPC (QP)4.4%0.621−0.3420.243
PID6.5%0.887−0.4760.356
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Ye, N.; Wang, D.; Dai, Y. Enhancing Autonomous Vehicle Lateral Control: A Linear Complementarity Model-Predictive Control Approach. Appl. Sci. 2023, 13, 10809. https://doi.org/10.3390/app131910809

AMA Style

Ye N, Wang D, Dai Y. Enhancing Autonomous Vehicle Lateral Control: A Linear Complementarity Model-Predictive Control Approach. Applied Sciences. 2023; 13(19):10809. https://doi.org/10.3390/app131910809

Chicago/Turabian Style

Ye, Ning, Duo Wang, and Yong Dai. 2023. "Enhancing Autonomous Vehicle Lateral Control: A Linear Complementarity Model-Predictive Control Approach" Applied Sciences 13, no. 19: 10809. https://doi.org/10.3390/app131910809

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