Preprint
Article

Research on Longitudinal Control of Electric Vehicle Platoons Based on Robust UKF-MPC

Altmetrics

Downloads

87

Views

35

Comments

0

A peer-reviewed article of this preprint also exists.

Submitted:

05 October 2024

Posted:

08 October 2024

You are already at the latest version

Alerts
Abstract
In a V2V communication environment, the control of electric vehicle platoons faces issues such as random communication delays, packet loss, and external disturbances, which affect sustainable transportation systems. In order to solve these problems and promote the development of sustainable transportation, a longitudinal control algorithm for the platoon based on robust Unscented Kalman Filter (UKF) and Model Predictive Control (MPC) is designed. First, a longitudinal kinematic model of the vehicle platoon is constructed, and discrete state-space equations are established. The robust UKF algorithm is derived by enhancing the UKF algorithm with Huber-M estimation. This enhanced algorithm is then used to estimate the state information of the leading vehicle. Based on the vehicle state information obtained from the robust UKF estimation, feedback correction and compensation are added to the MPC algorithm to design the robust UKF-MPC longitudinal controller. Finally, the effectiveness of the proposed controller is verified through CarSim/Simulink joint simulation. The simulation results show that in the presence of communication delay and data loss, the robust UKF-MPC controller outperforms the MPC and UKF-MPC controllers in terms of MSE and IAE metrics for vehicle spacing error and acceleration tracking error, and exhibits stronger robustness and stability.
Keywords: 
Subject: Engineering  -   Automotive Engineering

1. Introduction

With the popularization of electric vehicles (EVs) and the rapid development of telematics, the intelligent control of EV platoons has become an important application in intelligent transportation systems. This technology can effectively improve transportation safety, enhance efficiency, and reduce energy consumption [1,2].
Through vehicle-vehicle (V2V) communication technology, vehicles can share information such as velocity and location to achieve collaborative control, thereby reducing traffic congestion and lowering the incidence of accidents [3]. In addition, electric vehicle platooning can reduce energy consumption and extend the range of electric vehicles by optimizing driving patterns and velocities. At the same time, platoon driving can also reduce the number of braking and acceleration events, further reducing energy consumption. However, the complexity of the traffic environment and the non-linear nature of the vehicle dynamics system pose various challenges, including communication delays, packet loss and external interference, which can adversely affect the vehicle behavior, thereby weakening platoon stability and increasing energy consumption [4,5].
To address these challenges and enhance the stability and control precision of vehicle platoons, numerous researchers have conducted studies. Yang et al. [6] addressed the robustness of cooperative adaptive cruise control (CACC) systems under cyber-attacks by proposing a method to utilize multiple V2V communication networks for data fusion and redundant transmission, and designing an H∞ controller to minimize the impact of sensor and channel noise on vehicle platoon performance. Li et al. [7] proposed a distributed nonlinear vehicle platoon longitudinal controller based on a third-order model for heterogeneous vehicle platoons in communication delay environments. Samii et al. [8] developed a linear predictive feedback Cooperative Adaptive Cruise Control (CACC) controller to address communication and actuator delays in heterogeneous platoons. Halder et al. [9] introduced a discrete-time distributed state feedback control strategy for homogeneous vehicle platoons with an undirected network topology, capable of resisting external disturbances and random continuous network packet losses. Wang et al. [10] proposed a control algorithm considering information freshness to improve the longitudinal stability of the platoon by adjusting the information weights of multiple front vehicles and predicting the headway spacing, in response to the problem of reduced driving stability of the intelligent networked vehicle platoon in complex traffic environments. Lu et al. [11] created a distributed model predictive control (DMPC) strategy to ensure platoon stability for nonlinear vehicle platoons with a unidirectional communication topology, considering sensor jitter, control delays, and errors in real vehicle conditions. Meng et al. [12] designed a robust MPC controller and a slip ratio controller to address control errors due to parameter uncertainties in platoon modeling and ensure the stability of following vehicles. Tian et al. [13] employed Model Predictive Control (MPC) and Long Short-Term Memory (LSTM) prediction methods to study communication delay compensation in vehicle coordination control under CACC systems. Wang et al. [14] proposed an improved MPC algorithm based on the Kalman Filter (KF) to tackle issues such as environmental disturbances, sensor noise, and poor stability in following time-varying speeds.
In summary, while research on the longitudinal control of EV platoons has progressed in addressing external interference, communication delay, and data packet loss, the randomness of these factors still impacts vehicle state accuracy and platoon stability. To solve these issues, this paper constructs a longitudinal kinematic model of a vehicle platoon and establishes discrete state-space equations. By introducing Huber-M estimation to enhance the UKF algorithm, vehicle state information within the platoon is accurately estimated. Based on this estimated state information, feedback correction compensation is integrated into the MPC algorithm to design a robust UKF-MPC longitudinal controller. Finally, the effectiveness of this controller is verified through CarSim/Simulink co-simulation.
In summary, although existing research has made some progress in the longitudinal control of electric vehicle platoons, it still faces the challenge of random factors such as communication delays and data packet loss, which can degrade the accuracy of vehicle state estimation and thereby affect the stability of the platoon. To overcome this challenge, this paper proposes a longitudinal control strategy based on robust UKF-MPC. The strategy effectively improves the UKF algorithm’s robustness to communication issues by introducing the Huber-M estimation method, thus achieving accurate estimation of the vehicle states within the platoon. In addition, this paper integrates a feedback correction and compensation into the MPC algorithm, which further improves the prediction accuracy of the model and enhances the controller’s robustness. Finally, the effectiveness of the proposed strategy is verified by CarSim/Simulink joint simulation, and the results show that the strategy can effectively cope with the communication delay and data packet loss problems, significantly improving the stability and control accuracy of the electric vehicle platoon, thereby reducing energy consumption, improving traffic efficiency, and enhancing traffic safety, and providing technological support for the construction of a green, efficient, and safe traffic system.

2. Problem Description

Consider a traffic scenario in which N electric vehicles form a platoon travelling in a straight line, as shown in Figure 1, where the leading vehicle is numbered i = 0 and the following vehicles behind are numbered i = 1,2 , . . . , N . The following vehicle in the platoon adopts the Predecessor Following (PF) communication topology form through the V2V communication technology to obtain the position, velocity, acceleration and other state information of the vehicle in front of it. The distance between the following vehicle and the front vehicle is obtained through on-board sensors (e.g., radar, camera, etc.).

3. Longitudinal Kinematic Model of the Vehicle Platoon

Based on the V2V communication and on-board sensor data, the Constant Time Headway (CTH) strategy is used to calculate the desired spacing between adjacent vehicles and consider the effect of time delay, introduce the first-order inertial link to describe the relationship between the actual acceleration and the desired acceleration, and establish the discrete time-domain relational equation:
d i 1 , i ( k + 1 ) = d i 1 , i ( k ) + v i 1 , i ( k ) T s 1 2 a i ( k ) T s 2 + 1 2 a i 1 ( k ) T s 2 v i 1 , i ( k + 1 ) = v i 1 , i ( k ) a i ( k ) T s + a i 1 ( k ) T s v i ( k + 1 ) = v i ( k ) + a i ( k ) T s a i ( k + 1 ) = ( 1 K T s τ ) a i ( k ) + K T s τ a i _ d e s ( k )
Where d i 1 , i represents the spacing between adjacent vehicles, v i 1 , i represents the relative velocity between adjacent vehicles, v i represents the velocity of vehicle i, a i represents the acceleration of vehicle i, a i _ d e s represents the desired acceleration of vehicle i, K represents the first-order system gain, and τ represents the inertial link time constant, k represents the current moment of the system, k+1 represents the next moment of the system, and T s represents the sampling time of the system.
Define x ( k ) = [ d i 1 , i ( k ) , v i 1 , i ( k ) , v i ( k ) , a i ( k ) ] as the state variable, u ( k ) = a i _ d e s ( k ) as the control variable, and w ( k ) = a i 1 ( k ) as the disturbance variable. Rewrite Equation (1) into the form of discrete state space equations:
x ( k + 1 ) = A o x ( k ) + B o u ( k ) + C o w ( k )
The coefficient matrix is A o = 1 T s 0 T s 2 2 0 1 0 T s 0 0 1 T s 0 0 0 1 K T s τ , B o = 0 0 0 K T s τ , C o = T s 2 T s 0 0 .

4. Platoon Longitudinal Controller Design

Design the longitudinal controller of vehicle i as an upper and low layer. The upper controller obtains the state information of the vehicle i-1 and the state information of the vehicle i through the V2V communication to decide the desired acceleration, The low controller controls the acceleration and deceleration of the vehicle i according to the desired acceleration. Considering that the V2V communication has the problems of random communication delay and data loss, the robust UKF algorithm is used to estimate the state information of the vehicle under the influence of the communication problem. The specific control framework is shown in Figure 2.

4.1. Robust UKF State Prediction Algorithm

Vehicle nonlinear systems:
x k = F ( x k 1 ) + w k z k = H ( x k ) + v k
where x k represents the state vector, z k represents the observation vector, F ( x k 1 ) represents the state transfer equation, H ( x k ) represents the observation equation, w k represents the system process noise, and v k represents the observation noise.
The specific steps of robust UKF are as follows:
  • Initialize the mean μ 0 and covariance P 0 of the initial state of the system x 0 .
    μ 0 = E ( x 0 ) P 0 = E ( x 0 x 0 ¯ ) ( x 0 x 0 ¯ ) T
2.
Calculate the sigma points and construct 2n+1 sigma points along with the corresponding weights.
χ k 1 j = x ^ k 1 , j = 0 x ^ k 1 + n + λ ( P k 1 ) j , j = 1 , , n x ^ k 1 n + λ ( P k 1 ) j , j = n + 1 , 2 n
where P k 1 represents the state estimation covariance array at k-1 time, ( P k 1 ) j represents the j-th column of the Cholesky decomposition of the P k 1 matrix, λ = α 2 ( n + κ ) n . λ represents the scale adjustment factor, n represents the number of dimensions of the system state, α and κ represent the distributional scaling parameters for determining the sampling points, and α = 1 , κ = 3 n .
3.
Forecast update.
Prediction system sigma point set:
χ k | k 1 j = F χ k 1 j , u k 1 μ ^ x , k = i = 0 2 n ω m j χ k | k 1 j P ¯ x , k = i = 0 2 n ω c j ( χ k | k 1 j μ ^ x , k ) × ( χ k | k 1 j μ ^ x , k ) T + Q k
where Q k represents the covariance matrix of the system process noise.
4.
Measurement update.
γ k | k 1 j = H χ k | k 1 j μ ^ z , k = i = 0 2 n ω m j γ k | k 1 j P ¯ z , k = i = 0 2 n ω c j ( γ k | k 1 j μ ^ z , k ) × ( γ k | k 1 j μ ^ z , k ) T + R k
where R k represents the covariance matrix of the system measurement noise.
5.
Calculate the gain.
Calculation of cross-covariances:
P ¯ x z , k = i = 0 2 n ω c j ( χ k | k 1 j μ ^ x , k ) × ( γ k | k 1 j μ ^ z , k ) T
Calculate the Kalman gain:
K k = P ¯ z , k P ¯ x z , k 1
6.
Huber-M estimation.
In order to improve the robustness of the UKF algorithm to outliers, Huber-M estimation is introduced. Huber-M estimation is a robust estimation method that can effectively reduce the impact of outliers on the estimation results.
Calculate the residuals:
e z , k = z k μ ^ z , k
where z k represents the actual measured value.
Set the threshold parameter:
δ = η P ¯ j j z , k
where η = η 1 + η 2 e z , k , η 1 and η 2 represent the tuning parameters and P ¯ j j z , k represents the diagonal element of the state estimation covariance matrix.
Calculate Huber weights for M estimation.
M ( j , j ) = δ e z , k ,   | e z , k | δ 1 ,   | e z , k | < δ
7.
Measurement correction.
μ ^ k = μ ^ x , k + M K k e z , k P k = P ¯ x , k M K k P ¯ z , k K k T
The robustness of UKF is enhanced by introducing Huber-M estimation to deal with the outliers in the observed data, which effectively handles the noise and outliers caused by factors such as communication delays and data loss, thus improving the estimation accuracy of vehicle state information.

4.2. Robust MPC upper Layer Controller

The state space equations for longitudinal kinematics have been obtained above. The workshop distance, workshop distance error, relative velocity between vehicle i-1 and vehicle i, and the velocity and acceleration of vehicle i are chosen as the outputs of the state equations of the system:
y ( k ) = [ d i 1 , i , δ d i 1 , i , v i 1 , i , v i , a i ] T
Thus, the system state output equation is obtained:
y ( k ) = D o x ( k ) + E
Its coefficient matrix is D o = 1 0 0 0 1 0 τ h 0 0 1 0 0 0 0 1 0 0 0 0 1 , E = 0 d m i n 0 0 0 T .
Introduce control quantities into the state equation to construct new state quantities:
X ( k ) = x ( k ) u ( k 1 )
Derive the new state space equation as:
X ( k + 1 ) = A x ( k ) + B Δ u ( k ) + C w ( k )
where A = A o B o 0 N u × N x I N u × N u , B = B I N u × N u , C = C 0 N u × 1 , Δ u k is the increment of the control quantity, N x is the dimension of the state quantity, and N u is the dimension of the control quantity.
The new system state output equation is derived as:
Y ( k ) = D X ( k ) + E
where D = D 0 , 0 N y × 1 , N y represents the dimension of the output quantity.

4.2.1. Feedback Control of Longitudinal Platooning Trajectory

Vehicles in the process of modeling, due to the interference of the external environment and the influence of the vehicle parameter error and other reasons, the established model has a certain mismatch, so the introduction of feedback control to compensate for the prediction error of the following model, improve the model’s prediction accuracy of the state of the following system, and improve the robustness of the controller.
Define the state-volume error between the state-volume and the state-prediction at moment k:
e ( k ) = X ( k ) X p ( k | k 1 )
where X ( k ) represents the actual state of vehicle i at moment k, and X p ( k | k 1 ) is the state prediction of the system for moment k at moment k-1.
At moment k-1, the system predicts the amount of state at the moment:
X p ( k | k 1 ) = A X ( k 1 ) + B Δ u ( k 1 ) + C w ( k 1 )
The state prediction is corrected at moment k by the state quantity error:
X p ( k + 1 | k ) = A X ( k ) + B Δ u ( k ) + C w ( k ) + F e ( k )
where F = d i a g ( f d i 1 , i , f v i 1 , i , f v i , f a i , f Δ u ) represents the correction matrix, and the value range of each element in F is (0, 1).

4.2.2. Predictive Model Derivation

Assuming that the prediction time domain of the system is N p and the control time domain is N c , and that the prediction time domain and the control time domain satisfy N p N c . Due to the introduction of the feedback correction, based on the discrete longitudinal motion state space Equation (21), a new model prediction equation of state can be obtained:
Y p ( k + N p | k ) = M D A X ( k ) + M D B Δ U ( k + N c | k ) + M D C W ( k + N p | k ) + M D F e ( k ) + M E
where Y p ( k + N p | k ) , W ( k + N p | k ) represent the output quantity matrix and disturbance quantity matrix of the system in the prediction time domain, and Δ U ( k + N c | k ) represents the control quantity matrix of the system in the control time domain.

4.2.3. Objective Function

In order to ensure that the vehicle travels at the desired speed and acceleration, maintains a safe distance between the vehicles, and improves the efficiency of the vehicle, the desired vehicle spacing, vehicle spacing error, relative velocity, velocity, and acceleration are selected as the objectives and the objective function is designed.
y r e f = d i 1 , i d e s , 0,0 , v i 1 , 0 T
The exponential decay function is introduced as the target function reference trajectory to ensure that the reference trajectory changes more smoothly close to the target value, and the target reference trajectory is:
y r e f k + i = Λ i y k + 1 Λ i y r e f
Where Λ = d i a g ( Λ d i 1 , i , Λ δ d i 1 , i , Λ v i 1 , i , Λ v i , Λ a i ) , Λ represents the coefficient matrix of the reference trajectory, and the value range of each element is (0,1).
The prediction matrix for the target reference trajectory is:
Y r e f ( k + N p | k ) = y r e f ( k + 1 | k ) y r e f ( k + 2 | k ) y r e f ( k + N p | k )
The comprehensive performance function is designed with the need for followability and comfort.
J = i = 1 N p Y p k Y r e f k Q 2 + i = 1 N c Δ U k R 2
Where Q = d i a g ( q d i 1 , i , q δ d i 1 , i , q v i 1 , i , q v i , q a i ) , Q represents the weight matrix of the output quantity, R represents the weight matrix of the control quantity increment.

4.2.4. System State Constraints

In order to satisfy the requirements of traveling safety, following, and ride comfort of the platoon longitudinal traveling system, the MPC algorithm is constrained to be able to satisfy multiple constraints at the same time by imposing constraints on the output, control, and incremental control quantities of the MPC algorithm.
The constraints to be satisfied during the control of the MPC algorithm are as follows:
d m i n d i 1 , i k d m a x δ d m i n δ d i 1 , i ( k ) δ d m a x δ v m i n v i 1 , i ( k ) δ v m a x v m i n v i ( k ) v m a x a m i n a i ( k ) a m a x u m i n u ( k ) u m a x Δ u m i n Δ u ( k ) Δ u m a x
where the parameters with min and max in the subscripts are the upper and lower bounds of the system constraints, respectively.
For solving the problem of no solution in the rolling optimization process of MPC algorithm, the hard constraints are relaxed by introducing relaxation factors and relaxation coefficients to extend the feasible domain of the solution, and the constraints are reduced to matrix form.
Y m i n u m i n Δ u m i n + ϕ m i n Y ϕ m i n u ϕ m i n Δ u ε Y u Δ u Y m a x u m a x Δ u m a x + ϕ m a x Y ϕ m a x u ϕ m a x Δ u ε
where ε represents the relaxation factor matrix, ϕ m i n Y , ϕ m a x Y , ϕ m i n u , ϕ m a x u , ϕ m i n Δ u , ϕ m a x Δ u is the relaxation coefficient matrix.

4.2.5. Optimization Problem Solving

To avoid the problem of constraint failure due to relaxation factors, a quadratic penalty term for the relaxation factors is introduced into the optimization objective function to limit the range of constraints due to relaxation, then the performance cost function is:
J T = J + ε T ρ ε
Where ρ = d i a g ( ρ d , ρ δ d , ρ δ v , ρ v , ρ a , ρ u , ρ Δ u ) , ρ represents the matrix of penalty coefficients for the relaxation factors.
Transform the performance cost function treatment into a quadratic programming online solution problem with constraints in the form shown below:
min 1 2 U ρ T H ρ U ρ + f ρ T U ρ s . t . A u U ρ T b u
where U ρ = Δ U ε , H ρ = H     ρ , f ρ T = f T 0 1 × ( N y + N u + 1 ) .
The upper controller decides the desired acceleration by means of a robust MPC control algorithm.

4.3. Low Level Controller

4.3.1. Inverse Dynamics Model

According to the vehicle longitudinal kinematics model, the vehicle longitudinal acceleration and deceleration equations of motion are obtained.
m i δ a i = F t F b F w F f F i
where m i represents the vehicle mass of vehicle i, δ represents the vehicle rotating mass conversion factor, F t represents the driving force, F b represents the desired braking force, F w represents the air resistance, F f represents the rolling resistance and F i represents the ramp resistance.
In drive mode, the desired torque of the drive motor:
T d e s = [ m i g ( f cos θ + sin θ ) + C D A v i 2 21.15 + m i δ a i ] r i i t η t
where g represents the acceleration of gravity, f represents the rolling resistance coefficient, θ represents the ramp angle, is the air resistance coefficient, C D represents the windward area, r i represents the rolling radius of the wheels, i t represents the main gear transmission ratio, η t represents the transmission efficiency of the power transmission system.
In braking mode, the desired brake master cylinder pressure:
P d e s = | m i g ( f cos θ + sin θ ) C D A v i 2 21.15 m i δ a i | 1 K b
where K b represents the coefficient of proportionality between braking force and brake master cylinder pressure.

4.3.2. PID Low Controller

As shown in Figure 2, the low controller part adopts the PID control algorithm, utilizes the form of feed-forward plus feedback, and controls the driving torque and braking pressure based on the inverse longitudinal dynamics model of the vehicle by means of the drive-brake switching strategy, which tracks the desired acceleration obtained from the upper controller.

5. Simulation Analysis

For validating the designed robust UKF-MPC longitudinal controller, a joint simulation platform based on CarSim/Simulink is built to simulate and analyze the longitudinal control of vehicle platoon.
The simulation scenario with no communication delay and no data loss is set up in Simulink, and the simulation scenario with random communication delay of 10~100 ms and communication data loss of 50% is set up by uniform random signal and variable transport delay. The fleet of vehicles containing one leading vehicle and three following vehicles is set up in CarSim, with the initial speed of the four vehicles being 0 m/s and the initial inter-vehicle spacing of 3 m. The main parameters of the vehicles used are shown in Table 1.
Set the target speed of the leading vehicle, including acceleration, uniform speed, deceleration of three kinds of driving conditions, the specific parameters are set as shown in Table 2.
The robust UKF-MPC longitudinal controller of this paper is compared and analyzed with the MPC longitudinal controller and the improved UKF-MPC longitudinal controller based on UKF in the scenarios with and without communication delay and data packet loss problems, and the simulation results are shown in Figure 3, Figure 4, Figure 5, Figure 6, Figure 7 and Figure 8.
To further evaluate the performance of the different controllers, their Mean Square Error (MSE) and Integral Absolute Error (IAE) in the presence of communication delays and data loss were compared for velocity, acceleration, and inter-vehicle spacing, as shown in Table 3 and Table 4.
Under the condition of no communication delay and packet loss, as shown in Figure 3 and Figure 4, the speed and acceleration under the three controllers can stably follow the speed and acceleration of the front vehicle to ensure the stability of the longitudinal motion of the vehicle platoon; however, when comparing the inter-vehicle spacing errors of the vehicles controlled by the three controllers, the inter-vehicle spacing error under the MPC longitudinal controller is about 0.1 m, that under the UKF-MPC longitudinal controller is about is 0.3 m, and the workshop distance error under the robust UKF-MPC longitudinal controller is about 0.04 m, as shown in Figure 5. It can be seen that the robust UKF-MPC longitudinal controller in this paper improves the control accuracy of the longitudinal motion of the vehicle platoon compared to the MPC longitudinal controller and the UKF-MPC longitudinal controller under the condition of no communication delay and packet loss.
Under the condition of communication delay and packet loss, as shown in Figure 6, the speeds under the three controllers can basically follow the speed of the front vehicle, but the speed of the vehicle controlled by the MPC longitudinal controller jerks at higher speeds; as shown in Figure 7, the acceleration under the MPC controller oscillates violently, the acceleration under the UKF-MPC longitudinal controller jerks slightly and the acceleration under the robust UKF-MPC longitudinal controller jerks less and is basically stable. As shown in Figure 8, the workshop distance error under the MPC longitudinal controller is about 3 m, and the oscillation is violent, the workshop distance error under the UKF-MPC longitudinal controller is about 0.35 m, and there is a jitter when the speed is higher, and the workshop distance error under the robust UKF-MPC longitudinal controller is about 0.045 m, and it is basically stable. It can be seen that the MPC control algorithm is not effective under the condition of having communication random delay and packet loss, while the UKF-MPC control algorithm and the robust UKF-MPC control algorithm can effectively solve the problem of communication delay and packet loss, but the robust UKF-MPC control algorithm is more stable and has higher accuracy. This shows that the robust UKF-MPC algorithm can effectively deal with problems such as random communication delays and data loss, thus ensuring the stability and safety of the fleet.
The results in Table 3 and Table 4 show that the robust UKF-MPC controller is able to maintain high control accuracy and stability in the face of disturbances such as communication delays and packet loss. Compared with the MPC controller and the UKF-MPC controller, the robust UKF-MPC controller has comparable values of MSE and IAE for velocity and acceleration, but significantly lower values of MSE and IAE for inter-vehicle distance error, and is less affected by communication disturbances. This is mainly due to the introduction of Huber-M estimation and feedback correction and compensation in the robust UKF-MPC controller, which improves the robustness of the state estimation by effectively identifying and handling outliers caused by communication delays and packet loss. Feedback correction and compensation can make real-time correction according to the state estimation error, so as to improve the control accuracy and stability.

6. Conclusions

In this paper, a robust UKF-MPC based longitudinal controller for electric vehicle platoon is designed and validated by simulation comparison with MPC longitudinal controller and UKF-MPC longitudinal controller for continuous acceleration and deceleration conditions with and without communication problems.
Simulation results show that the robust UKF-MPC controller proposed in this paper reduces the vehicle inter-vehicle distance error from 0.1m (MPC) and 0.3m (UKF-MPC) to 0.04m, with comparable values of MSE and IAE for velocity and acceleration, compared to the MPC and UKF-MPC longitudinal controllers, indicating that the controller has a higher control accuracy without communication problems, the control accuracy is higher. In the presence of communication delays and data loss, the MSE and IAE values of the MPC longitudinal controller in terms of acceleration and vehicle spacing increased significantly, with inter-vehicle spacing errors as high as 3m and violent oscillations. The robust UKF-MPC longitudinal controller maintains the inter-vehicle distance error at about 0.045m and is basically stable, indicating that the controller maintains good control accuracy and stability in the presence of communication problems. This proves that the robust UKF-MPC longitudinal controller can effectively solve the problems of random communication delay, data packet loss, and external interference, which contributes to the development of sustainable transportation systems.

Author Contributions

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

Funding

This research was funded by National Natural Science Foundation of China (52262052) and Innovation-driven Major Project of Guangxi Province (AA22372, AA23062003).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Data are contained within the article.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Indu K, Aswatha Kumar M. Electric vehicle control and driving safety systems: A review. IETE Journal of Research. 2023, 69, 482–498. [CrossRef]
  2. Caruntu C F, Braescu C, Maxim A, Rafaila R. C; Tiganasu A. Distributed model predictive control for vehicle platooning: A brief survey. ICSTCC. 2016, 644–650. [CrossRef]
  3. Tang C, Xia J, Zhang M, Wu L. Research on Event-Triggered Control of Heterogeneous Cooperative Vehicle Platoons Considering Time Delay. Journal of Northeastern University. 2024, 45, 540–547. [CrossRef]
  4. Shen Z, Liu Y, Li Z, Wu Y. Distributed vehicular platoon control considering communication delays and packet dropouts. Journal of the Franklin Institute. 2024, 361, 106703. [CrossRef]
  5. Zhao C, Cai L, Cheng P. Stability analysis of vehicle platooning with limited communication range and random packet losses. Internet of Things Journal. 2020, 8, 262–277. [CrossRef]
  6. Yang T, Murguia C, Nešić D, Lv C. A Robust CACC Scheme Against Cyberattacks Via Multiple Vehicle-to-Vehicle Networks. IEEE Transactions on Vehicular Technology. 2023, 72, 11184–11195. [CrossRef]
  7. Li Y, He C, Zhu H, Zheng T. Nonlinear longitudinal control for heterogeneous connected vehicle platoon in the presence of communication delays. Acta Automatica Sinica. 2021, 47, 2841−2856.
  8. Samii A, Bekiaris-Liberis N. Robustness of string stability of linear predictor-feedback CACC to communication delay. ITSC. 2023, pp. 4853-4858. [CrossRef]
  9. Halder K, Gillam L, Dixit S, Mouzakitis A, Fallah S. Stability Analysis With LMI Based Distributed H∞ Controller for Vehicle Platooning Under Random Multiple Packet Drops. IEEE transactions on intelligent transportation systems. 2022, 23, 23517−23532. [CrossRef]
  10. Wang J, Qi C, Luo D, Wang H, Ding W. Longitudinal Stability Control Algorithm of Vehicle Platooning Based on Time-Varying Information Transmission Delays. Transactions of Beijing institute of Technology, 2024, 44, 828−837. [CrossRef]
  11. Lu R, Hu J, Chen R. Cooperative adaptive cruise control of intelligent vehicles based on DMPC. Autom Eng. 2021, 43, 1177−1186. [CrossRef]
  12. Meng Jin, Li Cong, Jing Hui, Tong Y, Feng H. Longitudinal Platoon Control of Electric Vehicle Based on Model Predictive Control. Journal of Dynamics and Control. 2023, 21, 44−53. [CrossRef]
  13. Tian B, Yao K, Wang Z, Gu G, Xu Z, Zhao X, Jing J. Communication delay compensation method of CACC platooning system based on model predictive control. Journal of Traffic and Transportation Engineering. 2022, 22, 361−381. [CrossRef]
  14. Wang Q, Jiang J, Lu Z, Zhang H. Research on cooperative adaptive cruise control strategy based on improved MPC. Journal of System Simulation. 2022, 34, 2087-2097. [CrossRef]
Figure 1. Schematic diagram of the longitudinal movement of the vehicle platoon.
Figure 1. Schematic diagram of the longitudinal movement of the vehicle platoon.
Preprints 120322 g001
Figure 2. Framework diagram of robust UKF-MPC based longitudinal controller.
Figure 2. Framework diagram of robust UKF-MPC based longitudinal controller.
Preprints 120322 g002
Figure 3. Variation of velocity from vehicle 0 to vehicle 3 under different controllers in an environment without communication delay and data loss.
Figure 3. Variation of velocity from vehicle 0 to vehicle 3 under different controllers in an environment without communication delay and data loss.
Preprints 120322 g003
Figure 4. Variation of acceleration from vehicle 0 to vehicle 3 under different controllers in an environment without communication delay and data loss.
Figure 4. Variation of acceleration from vehicle 0 to vehicle 3 under different controllers in an environment without communication delay and data loss.
Preprints 120322 g004
Figure 5. Variation of spacing error from vehicle 0 to vehicle 3 under different controllers in an environment without communication delay and data loss.
Figure 5. Variation of spacing error from vehicle 0 to vehicle 3 under different controllers in an environment without communication delay and data loss.
Preprints 120322 g005
Figure 6. Variation of velocity from vehicle 0 to vehicle 3 under different controllers with 10~100 ms random communication delay and 50% data packet loss.
Figure 6. Variation of velocity from vehicle 0 to vehicle 3 under different controllers with 10~100 ms random communication delay and 50% data packet loss.
Preprints 120322 g006
Figure 7. Variation of acceleration from vehicle 0 to vehicle 3 under different controllers with 10~100 ms random communication delay and 50% data packet loss.
Figure 7. Variation of acceleration from vehicle 0 to vehicle 3 under different controllers with 10~100 ms random communication delay and 50% data packet loss.
Preprints 120322 g007
Figure 8. Variation of spacing error from vehicle 0 to vehicle 3 under different controllers with 10~100 ms random communication delay and 50% data packet loss.
Figure 8. Variation of spacing error from vehicle 0 to vehicle 3 under different controllers with 10~100 ms random communication delay and 50% data packet loss.
Preprints 120322 g008
Table 1. Main vehicle parameters.
Table 1. Main vehicle parameters.
Vehicle parameters numerical value
Vehicle quality, m i 1270 kg
Vehicle length, l i 4 m
Wheel rolling radius, r i 0.325 m
Vehicle windward surface area, A 2.3 m2
Atmospheric drag coefficient, C D 0.342
Transmission efficiency, η t 0.9
Rolling resistance coefficient, f 0.02
Table 2. Target speeds for leading vehicles.
Table 2. Target speeds for leading vehicles.
Simulation   time   ( t / s ) Target   velocity   ( v 0 _ d e s / m / s )
0≤t≤5 2t
5<t≤15 10
15<t≤25 10+2.5(t-15)
25<t≤35 35
35<t≤45 35-2(t-35)
45<t≤55 15
55<t≤65 15+2.5(t-55)
65<t≤75 40
75<t≤85 40-3.5(t-75)
85<t≤100 5
Table 3. Comparison of the performance of different controllers in different situations: Mean Square Error (MSE) for velocity, acceleration and spacing.
Table 3. Comparison of the performance of different controllers in different situations: Mean Square Error (MSE) for velocity, acceleration and spacing.
Controller Delay (ms) Data loss rate (%) MSE of velocity MSE of acceleration MSE of spacing
MPC 0 0 2.61 0.19 6.54 × 10 4
UKF-MPC 0 0 3.14 0.23 9.02 × 10 3
Robust UKF-MPC 0 0 3.10 0.22 1.34 × 10 4
MPC 10~100 50 3.01 1.00 0.43
UKF-MPC 10~100 50 3.56 0.26 1.19 × 10 2
Robust UKF-MPC 10~100 50 3.53 0.24 2.42 × 10 4
Table 4. Comparison of the performance of different controllers in different situations: Integral Absolute Error (IAE) for velocity, acceleration and spacing.
Table 4. Comparison of the performance of different controllers in different situations: Integral Absolute Error (IAE) for velocity, acceleration and spacing.
Controller Delay (ms) Data loss rate (%) IAE of velocity IAE of acceleration IAE of spacing
MPC 0 0 1.15 × 10 4 2.49 × 10 3 170.78
UKF-MPC 0 0 1.26 × 10 4 2.79 × 10 3 737.33
Robust UKF-MPC 0 0 1.25 × 10 4 2.74 × 10 3 91.38
MPC 10~100 50 1.26 × 10 4 5.61 × 10 3 3.96 × 10 3
UKF-MPC 10~100 50 1.34 × 10 4 2.99 × 10 3 828.97
Robust UKF-MPC 10~100 50 1.34 × 10 4 2.94 × 10 3 116.80
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.
Copyright: This open access article is published under a Creative Commons CC BY 4.0 license, which permit the free download, distribution, and reuse, provided that the author and preprint are cited in any reuse.
Prerpints.org logo

Preprints.org is a free preprint server supported by MDPI in Basel, Switzerland.

Subscribe

© 2024 MDPI (Basel, Switzerland) unless otherwise stated