Next Article in Journal
Inverse Dynamics-Based Motion Planning for Autonomous Vehicles: Simultaneous Trajectory and Speed Optimization with Kinematic Continuity
Next Article in Special Issue
Research on Model Identification of Permanent Magnet DC Brushless Motor Based on Auxiliary Variable Subspace Identification Algorithm
Previous Article in Journal
Experimental Study on Distributed Measurement of Internal Pressure in Lithium-Ion Batteries Using Thin-Film Sensors
Previous Article in Special Issue
Research on the Performance of Vehicle Lateral Control Algorithm Based on Vehicle Speed Variation
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Research on Robust Adaptive Model Predictive Control Based on Vehicle State Uncertainty

School of Mechanical Engineering, Beijing University of Science and Technology, Beijing 100083, China
*
Author to whom correspondence should be addressed.
World Electr. Veh. J. 2025, 16(5), 271; https://doi.org/10.3390/wevj16050271
Submission received: 7 March 2025 / Revised: 24 April 2025 / Accepted: 13 May 2025 / Published: 14 May 2025

Abstract

:
To address the performance degradation in model predictive control (MPC) under vehicle state uncertainties caused by external disturbances (e.g., crosswinds and tire cornering stiffness variations) and rigid constraint conflicts, we propose a robust MPC framework with adaptive weight adjustment and dynamic constraint relaxation. Traditional MPC methods often suffer from infeasibility or deteriorated tracking accuracies when handling model mismatches and disturbances. To overcome these limitations, three key innovations are introduced: a three-degree-of-freedom vehicle dynamic model integrated with recursive least squares-based online estimation of tire slip stiffness for real-time lateral force compensation; an adaptive weight adjustment mechanism that dynamically balances control energy consumption and tracking accuracy by tuning cost function weights based on real-time state errors; and a dynamic constraint relaxation strategy using slack variables with variable penalty terms to resolve infeasibility while suppressing excessive constraint violations. The proposed method is validated via ROS (noetic)–MATLAB2023 co-simulations under crosswind disturbances (0–3 m/s) and varying road conditions. The results show that the improved algorithm achieves a 13% faster response time (5.2 s vs. 6 s control cycles), a 15% higher minimum speed during cornering (2.98 m/s vs. 2.51 m/s), a 32% narrower lateral velocity fluctuation range ([−0.11, 0.22] m/s vs. [−0.19, 0.22] m/s), and reduced yaw rate oscillations ([−1.8, 2.8] rad/s vs. [−2.8, 2.5] rad/s) compared with a traditional fixed-weight MPC algorithm. These improvements lead to significant enhancements in trajectory tracking accuracy, dynamic response, and disturbance rejection, ensuring both safety and efficiency in autonomous vehicle control under complex uncertainties. The framework provides a practical solution for real-time applications in intelligent transportation systems.

1. Introduction

In recent years, advancements in intelligent perception and decision-making technologies have driven the rapid development of autonomous driving systems [1]. The continuous evolution of algorithms enables autonomous driving systems to simulate human drivers’ cognitive and decision-making processes [2], achieving precise and efficient path planning in complex dynamic environments [3]. Concurrently, the widespread application of advanced sensors such as depth cameras [4] and lidar has endowed autonomous vehicles with high-precision environmental perception capabilities [5], establishing a solid foundation for safe and reliable autonomous navigation [6]. In recent years, countries around the world have significantly increased research investments into autonomous automotive driving technologies, focusing on achieving smooth and coherent vehicle control through advanced control algorithms [7], thereby enhancing the stability and reliability of autonomous driving systems [8,9]. Against this backdrop, autonomous driving technology has emerged as a core driver of automotive industry development [10], steering the sector toward a more intelligent, efficient, and sustainable future.
In the study of path-tracking control algorithms, common methodologies include PID control, linear quadratic regulator (LQR), and model predictive control (MPC). PID control, a classical approach, features a simple structure and ease of implementation, effectively addressing basic system dynamics [11]. However, PID control struggles to achieve optimal performance in complex dynamic environments [12], particularly in multivariate or nonlinear systems [13]. In contrast, LQR transforms control problems into optimization tasks [14], balancing control performance and system states through appropriate weighting to improve stability and tracking accuracy [15]. Its primary limitations lie in the requirement for precise linear models over large state spaces [16,17] and poor adaptability to parameter variations. MPC, a model-based advanced control technique, demonstrates more significant advantages [18,19]. By optimizing a multivariate objective function, MPC computes optimal control inputs in real time while considering system dynamic constraints [20,21]. Compared with LQR, MPC dynamically adjusts control strategies at each time step while ensuring system stability [22,23], with particularly prominent advantages in handling nonlinear or multi-constrained systems [24]. MPC not only integrates multiple control objectives effectively [25,26,27] but also performs receding-horizon optimization based on real-time system states [28], thereby achieving superior path-tracking performance [29]. For complex path-tracking problems involving multiple constraints and dynamic variations, MPC provides more robust and optimized solutions [30,31]. Consequently, MPC has become a critical research direction in modern autonomous vehicle control and has been widely applied to various path-tracking and trajectory optimization tasks [32].
This study focuses on enhancing vehicle trajectory-tracking smoothness by addressing state uncertainties and improving control algorithm adaptability. The proposed algorithmic improvements are validated through co-simulation experiments using ROS and MATLAB:
  • Robust MPC (RMPC) incorporates uncertainty modeling to enhance system adaptability to external disturbances (e.g., crosswinds, slippery road surfaces, and adaptive variations in tire cornering stiffness).
  • Uncertainty characterization embeds robust optimization strategies into the MPC objective function and constraints, ensuring controller stability across diverse operating conditions.
  • The adaptive soft-constraint strategy employs a constraint relaxation optimization method, introducing slack variables and penalty terms into the objective function, which allows for controlled relaxation of constraints within safe boundaries, ensuring MPC feasibility in complex scenarios while significantly improving algorithmic adaptability.

2. Vehicle Uncertainty Modeling

The intricacy of vehicle dynamic models has a substantial effect on both the design of controllers and the precision of simulations. High-fidelity models incorporating transmission systems, powertrain systems, and tire subsystems can more authentically replicate actual vehicle dynamic characteristics [33,34,35,36,37,38,39,40]. However, in applications such as trajectory planning and vehicle control, overly intricate models introduce substantial computational burdens. This necessitates judicious design trade-offs between model fidelity and computational efficiency to achieve optimal performance in real-time control systems. The workflow of the model predictive controller is shown in Figure 1.
Based on the working scenarios of vehicles, this study simplifies the complex vehicle dynamic model [41] reasonably under the premise of ensuring real-time, stable, and effective path-tracking control for medium-speed and slow vehicles and effectively improving their accuracy. At the same time, the longitudinal, lateral, and yaw motion characteristics of a vehicle are demonstrated. To make the model simpler and to optimize and reduce the difficulty of the calculation process, some reasonable assumptions are proposed:
  • The influence of vertical motion during vehicle operation can be ignored;
  • The influence of the vehicle steering system can be ignored, and the front-wheel angle can be used as the control input;
  • The influence of the front-wheel driving force on the vehicle yaw motion can be ignored;
  • The influence of aerodynamics on the overall vehicle motion can be ignored.
To analyze a vehicle’s motion and stability during steering, a dynamic model incorporating tire slip is used. The coordinate system for the ground is represented by XOY, while the vehicle body coordinate system is denoted xoy. The steering angle of the front wheels is represented by δf, and φ indicates the yaw angle of the vehicle. The yaw rate is denoted φ ˙ , with αf and αr representing the sideslip angles of the front and rear wheels, respectively. The center of mass’s sideslip angle is β. The speeds of the front and rear wheels, along with the center of mass, in the vehicle body coordinate system are represented by Vf, Vr, and V, respectively. Lateral forces at the front and rear wheels are denoted Fcr and Fcf, while longitudinal forces are represented by Flf and Flr. The distances from the center of mass to the front and rear wheels are denoted a and b, respectively. All the symbols and labels have been marked in Figure 2.
According to Newton’s second law, under the assumptions of the small-angle and linear tire model combined with the vehicle body coordinate formula, the three-degree-of-freedom dynamic model of the vehicle is obtained:
y ¨ = 2 m C c f × δ f y ˙ + a φ ˙ x ˙ + C c r × b φ ˙ y ˙ x ˙ x ˙ φ ˙ x ¨ = 2 m C l f × s f + C l r × s r C c f × δ f y ˙ + a φ ˙ x ˙ × δ f + y ˙ φ ˙ φ ¨ = 2 l Z a × C c f × δ f y ˙ + a φ ˙ x ˙ b × C c r × b φ ˙ y ˙ x ˙ Y ˙ = x ˙ s i n φ + y ˙ c o s φ X ˙ = x ˙ c o s φ y ˙ s i n φ
The vehicle state quantity ξ and control quantity u are:
ξ = [ y ˙ , x ˙ , φ , φ ˙ , Y , X ] T u = [ δ f ]

3. Adaptive Control Strategy for Robust MPC

3.1. Online Estimation and Compensation Strategy for Tire Sideslip Stiffness

To ensure stability, safety, and control accuracy during vehicle operation, this study takes into account the relationship between the slip angle, slip force, and stiffness of vehicle tires. By using the recursive least squares method, the estimated value of the stiffness of a tire slip is obtained based on historical data of slip force and slip angle. The regression expression equation of slip force and stiffness is as follows:
Y m ( k ) = φ T ( k ) ϕ ( k ) + e ( k )
In this formula, Ym(k) represents the output vector, namely the sideslip force; φ(k) represents the sideslip angle vector; Φ(k) is the parameter vector to be estimated, namely the sideslip stiffness; and e(k) is the noise vector.
The initial estimated value Φ(k) is set to zero, and then the covariance matrix P(0) is initialized and set to the identity matrix.
K ( k ) = P ( k 1 ) φ ( k ) λ + φ ( k ) T P ( k 1 ) φ ( k ) 1
Here, λ is the memory factor, which controls the weight of historical data and is set to a value of 0.9.
The estimated value Φ(k) is updated as follows:
ϕ ( k ) = ϕ ( k 1 ) + K ( k ) y ( k ) φ ( k ) T ϕ ( k 1 )
The covariance matrix P(k) is updated as follows:
P ( k ) = 1 λ P ( k 1 ) K ( k ) φ ( k ) T P ( k 1 )
The above steps are repeated until convergence is achieved and an accurate estimate is obtained.

3.2. Design of an MPC Controller

Based on a three-dimensional dynamic model of the vehicle, a nonlinear vehicle dynamic state equation can be established:
ξ ˙ = f ( ξ , u ) η = C ξ
Since the vehicle dynamic model is a nonlinear model, to simplify calculations, the running speed of the controller is enhanced and its real-time performance is ensured. At this point (ξ0,u0), the Taylor expansion method is utilized to linearize the above equation.
ξ ˙ = f ( ξ 0 , u 0 ) + f ξ | ξ 0 , u 0 ( ξ ξ 0 ) + f u | ξ 0 , u 0 ( u u 0 )
The linear state space equation of vehicle dynamics is therefore as follows:
ξ ˙ = A ξ + B u η = C ξ
Here, A is the state matrix, B is the control matrix, η is the output vector, and C is the output matrix. Both A and B are Jacobian matrices composed of partial derivatives, and c c r ¯ and C c r ¯ are the estimated lateral stiffnesses:
A = 2 C c f ¯ + C c r ¯ m x ˙ φ ˙ + 2 m C c f ( a φ ˙ + y ˙ ) x ˙ 2 C c r ( b φ ˙ y ˙ ) x ˙ 2 0 x ˙ + 2 m ( C c f ¯ a x ˙ + C c r ¯ b x ˙ ) 0 0 0 1 0 0 0 0 0 0 0 1 0 0 2 ( C c f ¯ a x ˙ + C c r ¯ b x ˙ ) I z 2 I z C c f a ( a φ ˙ + y ˙ ) x ˙ 2 + C c r b ( b φ ˙ y ˙ ) x ˙ 2 0 2 I z C c f ¯ a 2 x ˙ C c r ¯ b 2 x ˙ 0 0 cos ( φ ) sin ( φ ) x ˙ cos ( φ ) y ˙ sin ( φ ) 0 0 0 sin ( φ ) cos ( φ ) x ˙ sin ( φ ) y ˙ cos ( φ ) 0 0 0
B = 2 C c f ¯ m , 0 , 0 , 2 a C c f ¯ I Z , 0 , 0 T     C = 1 0 0 0 0 0 0 0 0 1 0 0
Because the vehicle operates at a constant speed, external disturbances primarily influence the vehicle’s lateral dynamics. In this context, we specifically examine the impact of crosswinds on vehicle motion. Crosswind disturbances affect both the lateral acceleration and yaw rate of the vehicle. As a natural environmental phenomenon, crosswinds can be measured using sensors installed on the vehicle. These sensors can detect the angle between the wind direction and the vehicle’s forward motion, as well as the current wind speed. The crosswind speed, denoted vwind, is measured in the vehicle’s coordinate system, and the angle of the crosswind relative to the vehicle’s longitudinal axis is represented by ϴwind.
The force of crosswinds on the lateral position of the vehicle is as follows:
F y . wind = 1 2 C d ρ A v wind 2 sin θ w i n d
By adding the crosswind disturbance term to the existing linear state space equation, the system is transformed into the following form:
ξ ˙ = A ξ + B u + G d η = C ξ
G is the disturbance matrix, which is used to describe the influence of crosswinds on the system, and d is the crosswind disturbance input, represented by Fy.wind. The disturbance matrix G is constructed as follows:
G = 1 m 0 0 L f I z 0 0 T
The disturbance vector d is defined as follows:
d = [ F y . wind ]
This state equation is used for the design of the controller.
Since the state equation is a continuous one, establishing a model predictive controller is impossible. Therefore, discretization processing is necessary.
x k + 1 = A d x k + B d u k + G d d k y k = C d x k
A d = 1 T s T s 2 2 0 0 0 0 1 2 ( C c f + C c r ) T s m x ˙ 2 ( C c f a C c r b ) T s m x ˙ 0 0 0 0 0 1 T s 0 0 0 0 0 0 1 x ˙ T s cos ( ϕ ˙ ) y ˙ T s sin ( ϕ ˙ ) 0 0 0 0 0 1
B d = 2 C c f T s m 2 a C c f T s I z 0 0 0 T
G d = T s m 0 0 b T s I z 0 T
Gd is a discrete perturbation matrix, which is mainly used to quantify the intensity and direction of the influence of perturbation dk on the system state variables.

3.3. Adaptive Optimization Objective Construction and Constraint Adjustment Strategy

The objective function is established as follows:
J = k 0 N 1 ( y k y k r ) T Q ( y k y k r ) + u k T R u k
Substituting y k = C d x k , the following is obtained:
J = k = 0 N 1 ( C d x k y k r ) T Q ( C d x k y k r ) + u k T R u k
For a prediction within a time domain of length N, the optimal control input sequence u 0 , u 1 , , u N 1 is obtained such that the system yk output approaches y k r , while the control input uk is kept as small as possible to reduce energy consumption or to enhance control stability.
In complex vehicle control scenarios, due to the strictness of system constraints, optimization problems often encounter infeasible solutions due to external disturbances (such as crosswind perturbations) or extreme working conditions. The main manifestations are trajectory deviation from the expected target, resulting in inaccurate MPC prediction, or control input exceeding the physical limits of the actuator. The fixed constraint boundaries of the front-wheel steering angle, a key control variable, may trigger optimization failure when facing dynamic disturbances, thereby threatening system stability. To address this challenge, this study innovatively integrates the recursive least squares method for real-time parameter estimation, the dynamic adjustment of the weight matrix driven by state error, and the adaptive penalty mechanism for relaxation variables. A novel constrained relaxation optimization strategy is proposed. This strategy intelligently adjusts the steering angle constraint boundaries (allowing a moderate relaxation of ±10%) and adopts a time-varying penalty factor to suppress constraint violations. It significantly improves the solution feasibility while maintaining system stability. Experiments show that under the same hardware platform, compared with traditional fixed relaxation weight methods (such as in reference [24]), this scheme not only maintains real-time computational efficiency but also improves lateral stability.
Assuming that the ideal condition for the steering angle of the front wheels is δ f δ m a x , to allow for slight violation of the constraint, we introduce a slack variable to transform the constraint into δ f δ m a x + ϵ δ :
J = k = 0 N 1 ( C d x k y k r ) T Q ( C d x k y k r ) + u k T R u k + λ ϵ δ 2
Q is the state error weight matrix, R is the control energy weight matrix, λ is the weight of control relaxation factor ϵδ, y k r is the expected trajectory, and ϵδ is the relaxation factor.
For better adjustment to different operating environments, we introduce a dynamic adjustment strategy, which dynamically adjusts the penalty term weighting factor λ through real-time feedback errors and perturbations. Specifically, we can adjust the weighting factor in the following way:
λ k + 1 = λ k 1 + α e k e max
Here, ek is the error at the current time step, emax is the maximum allowable error, and α is the gain factor. This dynamic adjustment method allows the system to automatically increase or decrease the relaxation weight based on the current error to adjust to different disturbances and operating conditions.
The final optimization and solution are obtained as follows:
min k = 0 N ( C d x k y k r ) T Q ( C d x k y k r ) + u k T R u k + λ ϵ δ 2
x k + 1 = A d x k + B d u k + G d d k δ f m i n ϵ k δ f δ f m a x + ϵ k ϵ k 0
The weight factors need to be reasonably adjusted to minimize the slack variables, as close to zero as possible, to avoid excessive relaxation of the constraints: if the weight is too large, the slack variables tend toward zero and the constraints become strict, which may lead to an unsolvable problem; however, if the weight is too small, the constraints may be violated, significantly affecting the stability of the system. Therefore, strict constraints and feasible solutions need to be balanced.

4. Experimental Co-Simulation

This study constructs a dynamic model of heavy-duty vehicles and a verification environment for control algorithms based on the ROS and MATLAB joint-simulation platform. The dynamic model adopts Simulink joint simulation architecture to establish a three-degree-of-freedom vehicle kinematic equation set including longitudinal force, lateral force, and moment. The ROS is employed to achieve real-time communication of sensor data and control instructions. The simulation scenarios are designed to encompass straight-line driving, curve tracking, and crosswind disturbance conditions. Herein, the crosswind disturbance intensity is set within a random fluctuation range of 0–3 m/s to simulate actual uncertainties. To verify the robustness of the proposed method, a comparative experiment is set up between the traditional equal-weight MPC and improved MPC algorithms, jointly optimizing the dynamic vehicle sideslip stiffness and relaxation factor proposed in this study. All experiments adopt the same initial state of 3 m/s and trajectory planning target. As depicted in Figure 3, the distance between the left and right boundaries of the track is 5 m and the road width is 1 m. The gray line represents the lane line, and the purple line represents the lane center line. The vehicle travels along the center line, accompanied by random trajectory fluctuations. The black dotted line in the lower-right corner of the figure marks the vehicle’s starting point, and the vehicle travels counterclockwise. The improved MPC and the traditional MPC algorithms are both subjected to comparative tests in this scenario, with a focus on the vehicle state during turning and straight-line driving.
Figure 4 shows the schematic diagram of the steering angle of the collaborative simulation vehicle. The simulation results indicate that the improved MPC algorithm significantly outperforms the traditional algorithm in steering angle control. The improved MPC algorithm demonstrates a faster dynamic response. When the vehicle enters a curve, the improved algorithm adopts a faster steering strategy to pass through the curve at a slightly reduced speed to ensure driving safety. The trajectory prediction line closely adheres to a safe boundary without any risk of crossing over, while the traditional MPC algorithm significantly reduces speed and undergoes oscillation attenuation. Additionally, the 5.2 s control cycle of the improved algorithm is 13% shorter than the traditional 6 s cycle. The relaxation factor mechanism effectively balances the strictness of the constraints and the feasibility of optimization, achieving a better trade-off between safety and efficiency.
Figure 5 is a vehicle speed chart, showing the following information. The speed comparison curve indicates that the improved MPC algorithm outperforms the traditional MPC algorithm in terms of dynamic speed planning ability. During the initial left-turn stage of the vehicle, the minimum speed of the improved MPC algorithm is higher than that of the traditional MPC algorithm, but stable driving is maintained. During the right-turn stage, the improved MPC algorithm controls the speed at 2.98 m/s through dynamic weight adjustments, while the traditional MPC algorithm experiences a significant speed drop to 2.51 m/s. During the subsequent second left-turn stage, the speed of the improved MPC algorithm is reduced to 2.86 m/s, with good controllability, while the speed of the traditional MPC algorithm drops to 2.53 m/s. During the third left-turn stage, the improved MPC algorithm still achieves high speeds compared with the traditional MPC algorithm. The improved MPC algorithm predicts the curvature change in the curve through state uncertainty modeling and allows for a brief overshoot in speed within a safe boundary. At the same time, the energy consumption and tracking accuracy requirements are balanced via 5.2 s short-cycle real-time optimization.
As can be seen from Figure 6, during lateral velocity control, both the improved and traditional MPC algorithms exhibit periodic fluctuation characteristics. However, the overall fluctuation in the improved MPC algorithm is relatively gentle, avoiding large changes within a short period of time that could cause instability in the vehicle. The fluctuation trend of the improved MPC algorithm is smooth, while the fluctuation range of the traditional MPC algorithm exceeds that of the improved MPC algorithm. The anti-interference ability of the improved MPC algorithm has therefore been significantly enhanced. The lateral velocity fluctuates within the range of [−0.11, 0.22], while the traditional MPC algorithm experiences control delay and a steady-state error increase due to model simplification, and the lateral velocity fluctuates within the range of [−0.19, 0.22]. This further validates the effectiveness of the improved MPC algorithm in achieving better control performance under complex working conditions by optimizing the constraint conditions or the prediction model.
The yaw rate varies over time, as shown in Figure 7 below. The improved and traditional MPC algorithms show significant differences in their dynamic response characteristics. The improved MPC algorithm allows for rapid convergence to the target state by optimizing the model and relaxing the constraints, indicating that it has a strong tracking ability for transient instructions. The traditional MPC algorithm, however, is very conservative in controlling the vehicle state, resulting in lags in its dynamic response and significantly limiting the performance of the vehicle. Overall, the improved MPC algorithm significantly improves the robustness and accuracy of yaw rate control by introducing more precise state estimation and constraint compensation mechanisms, fluctuating within the range of [−1.8, 2.8]. In contrast, the traditional MPC algorithm fluctuates within the range of [−2.8, 2.5] due to model simplification and control strategy limitations and has clear shortcomings in dynamic performance.
The improved MPC algorithm demonstrates significant advantages over the traditional MPC algorithm in terms of dynamic response, speed control, and stability. The traditional MPC algorithm is relatively conservative, with sluggish steering responses, significant speed reductions when entering a curve, and an oscillation attenuation process. As a result, the speed fluctuation is large, which affects the driving efficiency and stability. In contrast, the improved MPC algorithm optimizes constraint handling and dynamic adjustment strategies, enhancing steering flexibility, achieving faster dynamic responses, and performing better in full-speed cornering and speed recovery. Moreover, the improved MPC algorithm exhibits better anti-interference abilities in lateral speed and yaw rate control, with smaller fluctuations, enhancing the vehicle’s stability in complex environments. Without deviations from the lane, the vehicle’s dynamic characteristics are fully utilized to improve path-tracking accuracy and control efficiency. Overall, the improved MPC algorithm not only ensures safety but also enhances the vehicle’s dynamic performance, achieving superior control effects. Table 1 shows the improvements made by our improved algorithm compared to the traditional algorithm.
The simulation experiment was performed on a high-performance mobile workstation with the following core hardware configuration.
CPU: AMD Ryzen 7 5800H (Advanced Micro Devices, Santa Clara, CA, USA) and a stable temperature of 49 °C under actual load provided efficient parallel computing capabilities to meet the real-time solution needs of complex dynamic models. Graphics card: an Nvidia GeForce RTX 3060 laptop GPU (Nvidia Corporation, Santa Clara, CA, USA) significantly improved the matrix computation and visual rendering efficiency in the simulation–ROS co-simulation.
This configuration performed well in the simulation and could stably handle the 3-DOF vehicle model, MPC optimization, and cross-platform data communication tasks described in this study, ensuring real-time algorithm validation and its reliability. The hardware performance margin is sufficient to support higher-dimensional models or more intensive sensor data simulation scenarios.

5. Results

This study proposes a robust adaptive MPC method to address vehicle control challenges in complex environments, with its effectiveness validated through theoretical analyses and simulation experiments. The main conclusions are summarized as follows.
  • Uncertainty modeling and robust optimization: By incorporating uncertainty modeling and robust optimization to characterize state uncertainties and by embedding robust constraints into the MPC framework, the proposed method significantly enhances the system’s resistance to external disturbances (e.g., crosswinds and variations in tire cornering stiffness). This approach reduces the impact of model errors on the control performance and strengthens the system’s robustness against uncertainties.
  • Adaptive constraint relaxation optimization mechanism: A flexible constraint conversion method is proposed based on the dynamic adjustment of penalty term weighting factors. By introducing slack variables, hard constraints are transformed into quantifiable soft constraints, resolving the infeasibility issues in traditional MPC caused by rigid constraints. Concurrently, adaptive penalty factors suppress excessive relaxation, achieving a balance between constraint flexibility and control freedom while ensuring system stability.
  • The engineering effectiveness of the improved algorithm was validated through an ROS–MATLAB co-simulation platform and real-vehicle tests. Under complex operating conditions involving crosswind disturbances and adaptive variations in tire cornering stiffness, the enhanced MPC algorithm demonstrated significant improvements in control input smoothness and vehicle operational efficiency, further confirming its potential for practical applications. Future research will explore dynamic weight allocation mechanisms in multi-objective optimization frameworks and will integrate online parameter identification techniques to improve adaptability to long-term variations. This study provides novel theoretical tools and practical methodologies for efficient and safe vehicle control.
This study provides an effective robust control solution for the safe driving of intelligent vehicles in complex road environments, which is suitable for curved-track tracking control in urban road scenarios. However, this study does not explicitly consider the delay characteristics of the powertrain, which may lead to performance limitations in high-precision speed-tracking applications. At the same time, the adaptability of the simplified dynamic model under extreme conditions still needs to be verified with further experiments. In contrast, the method proposed in [41] provides a systematic solution framework for the delay compensation problem of the electric vehicle powertrain system, and this method can be effectively applied in scenarios requiring high-precision speed tracking. Based on the limitations of existing research, our future research will focus on the following directions.
  • Online parameter identification and adaptive optimization: Dynamic real-time calibration of model parameters can be achieved by integrating delayed online estimation technology from the literature and the adaptive weight adjustment strategy proposed in this study.
  • Computational efficiency optimization: Aiming to address the computational burden brought about by the extended state MPC algorithm, efficient implementation schemes based on edge computing or sparse optimization algorithms will be studied to further improve the real-time performance of the control system.
  • Full-dimensional collaborative control: By combining the advantages of the two MPC algorithms of horizontal trajectory tracking and longitudinal speed control, a global vehicle dynamic coupling model will be constructed, and track–speed collaborative optimization control under complex driving scenarios can finally be achieved.

Author Contributions

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

Funding

This research was funded by the technology development project “Research on Intelligent Vehicle Path Planning and Control System”, Funding Number: BJLG2023458, jointly established by Qilu University of Technology and the Beijing Institute of Technology Frontier Technology.

Data Availability Statement

The data are contained within this article.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Yang, W.; Chen, Y.; Lian, C. Integrated Spatial Kinematics-Dynamics Model Predictive Control for Collision-Free Autonomous Vehicle Tracking. Actuators 2024, 13, 153. [Google Scholar] [CrossRef]
  2. Ji, Y.B.; Zhang, Y.; Liu, Z.L. Design of Follow-up Control in Auto-tracking Smart Car System. In Proceedings of the International Conference on Mechatronics and Industrial Informatics (ICMII 2013), Guangzhou, China, 13–14 March 2013; IEEE: Guangzhou, China, 2013; pp. 234–240. [Google Scholar]
  3. Jond, H.B.; Platos, J. A Fast Trajectory Tracking Control Design for Autonomous Driving. In Proceedings of the 7th International Conference on Robotics and Mechatronics (ICRoM), Tehran, Iran, 20–21 November 2019; Sharif University of Technology: Tehran, Iran, 2019; pp. 45–52. [Google Scholar]
  4. Li, Y.; Moreau, J.; Ibanez-Guzman, J. Emergent Visual Sensors for Autonomous Vehicles. IEEE Trans. Intell. Transp. Syst. 2023, 24, 4716–4737. [Google Scholar] [CrossRef]
  5. Wei, P.; Zeng, Y.; Ouyang, W.; Zhou, J. Multi-Sensor Environmental Perception and Adaptive Cruise Control of Intelligent Vehicles Using Kalman Filter. IEEE Trans. Intell. Transp. Syst. 2024, 25, 3098–3107. [Google Scholar] [CrossRef]
  6. Tang, X.; Yang, K.; Wang, H.; Yu, W.; Yang, X.; Liu, T.; Li, J. Driving Environment Uncertainty-Aware Motion Planning for Autonomous Vehicles. Chin. J. Mech. Eng. 2022, 35, 120. [Google Scholar] [CrossRef]
  7. Jeong, Y. Integrated Vehicle Controller for Path Tracking with Rollover Prevention of Autonomous Articulated Electric Vehicle Based on Model Predictive Control. Actuators 2023, 12, 41. [Google Scholar] [CrossRef]
  8. Subari, M.A.; Hudha, K.; Abd Kadir, Z.; Dardin, S.M.F.S.M.; Amer, N.H. Development of Path Tracking Controller for an Autonomous Tracked Vehicle. In Proceedings of the 16th IEEE International Colloquium on Signal Processing and its Applications (CSPA), Langkawi, Malaysia, 28–29 February 2020; IEEE: Langkawi, Malaysia, 2020; pp. 123–130. [Google Scholar]
  9. Zhao, W.Q. Real-Time Model Predictive Control of Path-Following for Autonomous Vehicles Towards Model Mismatch and Uncertainty. Control Eng. Pract. 2024, 142, 105678. [Google Scholar] [CrossRef]
  10. Dong, Z.; Shi, W.; Tong, G.; Yang, K. Collaborative Autonomous Driving: Vision and Challenges. In Proceedings of the International Conferencon Connected and Autonomous Driving (MetroCAD), Detroit, MI, USA, 27–28 February 2020; SAE International: Detroit, MI, USA, 2020; pp. 89–95. [Google Scholar]
  11. Bhat, V.S.; Kumar, V.; Dayanand, N.; Shettigar, A.; Nikhitha. Comparative Study of PID Control Algorithms for an Electric Vehicle. In Proceedings of the 2nd International Conference on Emerging Trends in Mechanical Engineering (ETIME), Mangaluru, India, 9–10 August 2019; Springer: Mangaluru, India, 2019; pp. 76–85. [Google Scholar]
  12. Peicheng, S.; Li, L.; Ni, X.; Yang, A. Intelligent Vehicle Path Tracking Control Based on Improved MPC and Hybrid PID. IEEE Access 2022, 10, 94133–94144. [Google Scholar] [CrossRef]
  13. Li, H.; Li, J.; Wang, R.; Luo, J. Path Planning and Tracking Strategy under Emergency for Vehicle Obstacle Avoidance System. In Proceedings of the 3rd International Conference on Robotics, Control and Automation Engineering (RCAE), Chongqing, China, 5–8 November 2020; IEEE: Chongqing, China, 2020; pp. 112–119. [Google Scholar]
  14. Yang, T.B.; Li, Z.; Feng, N.; Chen, L. Intelligent Vehicle Lateral Control Method Based on Feedforward+ Predictive LQR Algorithm. Actuators 2021, 10, 228. [Google Scholar] [CrossRef]
  15. Deng, Z.W.; Zhao, Q.X.; Zhao, Y.Q.; Wang, B.H.; Gao, W.; Kong, X.X. Active LQR Multi-Axle-Steering Method for Improving Maneuverability and Stability of Multi-Trailer Articulated Heavy Vehicles. Int. J. Automot. Technol. 2022, 23, 939–955. [Google Scholar] [CrossRef]
  16. Zhou, Z.; Bao, Y.; Fan, J. Research on Improving Vehicle Stability Control Using Enhanced LQR Method. In Proceedings of the 3rd International Conference on Energy and Power Engineering, Control Engineering (EPECE), Chengdu, China, 23–25 February 2024; IEEE: Chengdu, China, 2024; pp. 234–241. [Google Scholar]
  17. Sun, Y.; Dai, Q.; Liu, J.; Zhao, X.; Guo, H. Intelligent Vehicle Path Tracking Based on Feedback Linearization and LQR under Extreme Conditions. In Proceedings of the 41st Chinese Control Conference (CCC), Hefei, China, 25–27 July 2022; IEEE: Hefei, China, 2022; pp. 678–685. [Google Scholar]
  18. Cui, K.; He, J.; Yao, X.; Gu, X. Adaptive Model Predictive Control Based on Stability Index for Path Tracking of Autonomous Vehicles Considering Model Error. Proc. Inst. Mech. Eng. Part C J. Mech. Eng. Sci. 2024, 238, 9372–9396. [Google Scholar] [CrossRef]
  19. Wang, X.H.; Han, M.; Gao, Z.; Li, L.; Miao, Z. Path Tracking and Obstacle Avoidance Algorithm Based on Model Predictive Control. In Proceedings of the 34th Chinese Control and Decision Conference (CCDC), Hefei, China, 15–17 August 2022; IEEE: Hefei, China, 2022; pp. 102–109. [Google Scholar]
  20. Jing, Z.Y.; Huang, W.; Ma, H. A Tracking Control Method for Collision Avoidance Trajectory of Autonomous Vehicle Based on Multi-Constraint MPC. Int. J. Veh. Des. 2021, 86, 106–123. [Google Scholar] [CrossRef]
  21. Wu, X.; Zhang, K.J.; Cheng, M. Optimal Control of Nonlinear Systems with Integer-Valued Control Inputs and Stochastic Constraints. Int. J. Robust Nonlinear Control 2022, 32, 10326–10346. [Google Scholar] [CrossRef]
  22. Yu, S.; Pan, X.; Georgiou, A.; Chen, B.; Jaimoukha, I.M.; Evangelou, S.A. A Robust Model Predictive Control Framework for Ecological Adaptive Cruise Control Strategy of Electric Vehicles. In Proceedings of the IEEE International Conference on Mechatronics (ICM), Loughborough, UK, 15–17 March 2023; IEEE: Loughborough, UK, 2023; pp. 88–95. [Google Scholar]
  23. Li, R. Preview Control with Dynamic Constraints for Autonomous Vehicles. Sensors 2021, 21, 5155. [Google Scholar] [CrossRef]
  24. Bujarbaruah, M.; Nair, S.H.; Borrelli, F. A Semi-Definite Programming Approach to Robust Adaptive MPC under State Dependent Uncertainty. In Proceedings of the 18th European Control Conference (ECC), St. Petersburg, Russia, 12–15 May 2020; IEEE: St. Petersburg, Russia, 2020; pp. 456–463. [Google Scholar]
  25. Cheng, S.; Li, L.; Chen, X.; Wu, J.; Wang, H.-D. Model-Predictive-Control-Based Path Tracking Controller of Autonomous Vehicle Considering Parametric Uncertainties and Velocity-Varying. IEEE Trans. Ind. Electron. 2021, 68, 8698–8707. [Google Scholar] [CrossRef]
  26. Iqbal, J. Electric Vehicle Cornering Stiffness & Lateral States Estimation Using Synchronized Adaptive Sliding Mode Observer and Kalman Filter. Int. Trans. J. Eng. Manag. Appl. Sci. Technol. 2021, 12, 234–248. [Google Scholar]
  27. Qi, G.X. Integrated Control Method for Path Tracking and Lateral Stability of Distributed Drive Electric Vehicles with Extended Kalman Filter-Based Tire Cornering Stiffness Estimation. J. Vib. Control 2024, 30, 567–582. [Google Scholar] [CrossRef]
  28. Guirguis, J.M.; Hammad, S.; Maged, S.A. Path Tracking Control Based on an Adaptive MPC to Vehicle. Int. J. Mech. Eng. Robot. Res. 2022, 11, 535–541. [Google Scholar]
  29. Li, H.; Li, B.; Yang, H.; Mu, C. Nonlinear Model Predictive Control for Time-Optimal Turning Around of an Autonomous Vehicle Under Steering Lag. IEEE/ASME Trans. Mechatron. 2025, 30, 577–586. [Google Scholar] [CrossRef]
  30. Meng, D.; Chu, H.; Tian, M.; Gao, B.; Chen, H. Real-Time High-Precision Nonlinear Tracking Control of Autonomous Vehicles Using Fast Iterative Model Predictive Control. IEEE Trans. Intell. Veh. 2024, 9, 3644–3657. [Google Scholar] [CrossRef]
  31. Liang, J.; Tian, Q.; Feng, J.; Pi, D.; Yin, G. A Polytopic Model-Based Robust Predictive Control Scheme for Path Tracking of Autonomous Vehicles. IEEE Trans. Intell. Veh. 2024, 9, 3928–3939. [Google Scholar] [CrossRef]
  32. Tan, W.; Wang, M.F.; Ma, K. Research on Intelligent Vehicle Trajectory Tracking Control Based on Improved Adaptive MPC. Sensors 2024, 24, 2316. [Google Scholar] [CrossRef] [PubMed]
  33. Widner, A.; Tihanyi, V.; Tettamanti, T. Framework for Vehicle Dynamics Model Validation. IEEE Access 2022, 10, 35422–35436. [Google Scholar] [CrossRef]
  34. Chen, S.P.; Chen, H.Y.; Negrut, D. Implementation of MPC-Based Path Tracking for Autonomous Vehicles Considering Three Vehicle Dynamics Models with Different Fidelities. Automot. Innov. 2020, 3, 386–399. [Google Scholar] [CrossRef]
  35. Kanchwala, H.; Viana Í, B.; Ceccoti, M.; Aouf, N. Model Predictive Tracking Controller for a High Fidelity Vehicle Dynamics Model. In Proceedings of the IEEE Intelligent Transportation Systems Conference (IEEE-ITSC), Auckland, New Zealand, 27–30 October 2019; IEEE: Auckland, New Zealand, 2019; pp. 112–120. [Google Scholar]
  36. Liu, J.; Jayakumar, P.; Overholt, J.L.; Stein, J.L.; Ersal, T. The Role of Model Fidelity in Model Predictive Control-Based Hazard Avoidance in Unmanned Ground Vehicles Using LiDAR Sensors. In Proceedings of the ASME Dynamic Systems and Control Conference (DSCC), Palo Alto, CA, USA, 21–23 October 2013; ASME: Palo Alto, CA, USA, 2013; pp. 234–241. [Google Scholar]
  37. Thakur, M.B.; Schmid, M. Efficient Uncertainty Mitigation in Automated Vehicles: Combining MPC with Model Reference Adaptive Control. In Proceedings of the 3rd Modeling, Estimation and Control Conference (MECC), Lake Tahoe, NV, USA, 2–5 October 2023; IEEE: Lake Tahoe, NV, USA, 2023; pp. 56–63. [Google Scholar]
  38. Gao, F.; Hu, Q.; Ma, J.; Han, X. A Simplified Vehicle Dynamics Model for Motion Planner Designed by Nonlinear Model Predictive Control. Appl. Sci. 2021, 11, 9887. [Google Scholar] [CrossRef]
  39. Kebbati, Y.; Puig, V.; Ait-Oufroukh, N.; Vigneron, V.; Ichalal, D. Optimized Adaptive MPC for Lateral Control of Autonomous Vehicles. In Proceedings of the 9th International Conference on Control, Mechatronics and Automation (ICCMA), Belval, Luxembourg, 11–14 November 2021; pp. 88–95. [Google Scholar]
  40. Yang, S.; Qian, Y.; Hu, W.; Xu, J.; Sun, H. Adaptive MPC-Based Lateral Path-Tracking Control for Automatic Vehicles. World Electr. Veh. J. 2024, 15, 95. [Google Scholar] [CrossRef]
  41. Lee, J.; Jo, K. Model Predictive Control with Powertrain Delay Consideration for Longitudinal Speed Tracking of Autonomous Electric Vehicles. World Electr. Veh. J. 2024, 15, 433. [Google Scholar] [CrossRef]
Figure 1. Control system flow.
Figure 1. Control system flow.
Wevj 16 00271 g001
Figure 2. Vehicle dynamic model.
Figure 2. Vehicle dynamic model.
Wevj 16 00271 g002
Figure 3. Vehicle simulation driving map.
Figure 3. Vehicle simulation driving map.
Wevj 16 00271 g003
Figure 4. Front-wheel angle comparison.
Figure 4. Front-wheel angle comparison.
Wevj 16 00271 g004
Figure 5. Longitudinal velocity comparison.
Figure 5. Longitudinal velocity comparison.
Wevj 16 00271 g005
Figure 6. Lateral velocity comparison.
Figure 6. Lateral velocity comparison.
Wevj 16 00271 g006
Figure 7. Yaw velocity comparison.
Figure 7. Yaw velocity comparison.
Wevj 16 00271 g007
Table 1. Comparison between the traditional and improved MPC algorithms.
Table 1. Comparison between the traditional and improved MPC algorithms.
Max SteeringMax Yaw RateMax Lateral VelocityMax Velocity
Conventional MPC0.3142.3350.2332.994
Proposed MPC0.0203.1020.2273.006
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

Li, Y.; Liu, L. Research on Robust Adaptive Model Predictive Control Based on Vehicle State Uncertainty. World Electr. Veh. J. 2025, 16, 271. https://doi.org/10.3390/wevj16050271

AMA Style

Li Y, Liu L. Research on Robust Adaptive Model Predictive Control Based on Vehicle State Uncertainty. World Electric Vehicle Journal. 2025; 16(5):271. https://doi.org/10.3390/wevj16050271

Chicago/Turabian Style

Li, Yinping, and Li Liu. 2025. "Research on Robust Adaptive Model Predictive Control Based on Vehicle State Uncertainty" World Electric Vehicle Journal 16, no. 5: 271. https://doi.org/10.3390/wevj16050271

APA Style

Li, Y., & Liu, L. (2025). Research on Robust Adaptive Model Predictive Control Based on Vehicle State Uncertainty. World Electric Vehicle Journal, 16(5), 271. https://doi.org/10.3390/wevj16050271

Article Metrics

Back to TopTop