Next Article in Journal
Research on Energy Saving for Hybrid Tractor Based on Working Condition Prediction and DDPG-Fuzzy Control
Previous Article in Journal
Torque Capability Enhancement of Interior Permanent Magnet Motors Using Filleting and Notching Stator
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Research on Active Collision Avoidance Control of Vehicles Based on Estimation of Road Surface Adhesion Coefficient

College of Automotive Engineering, Shandong Jiaotong University, Jinan 250357, China
*
Author to whom correspondence should be addressed.
World Electr. Veh. J. 2025, 16(9), 489; https://doi.org/10.3390/wevj16090489
Submission received: 23 June 2025 / Revised: 18 August 2025 / Accepted: 26 August 2025 / Published: 27 August 2025

Abstract

In order to solve the problem that intelligent vehicle active collision avoidance systems have different decision-making results under different road conditions, the square-root cubature Kalman filtering algorithm is used to estimate the road adhesion coefficients, which are introduced into the safety distance model and combined with the fireworks algorithm for braking and steering weight coefficient allocation to ensure that the vehicle can safely avoid collision. The simulation results show that the square-root cubature Kalman filter has higher estimation accuracy and robustness compared with the cubature Kalman filter, and a more reasonable collision avoidance control can be adopted in the subsequent collision avoidance control. Therefore, the proposed new estimation method of road adhesion coefficients proves effective in mitigating vehicle collision risks.

1. Introduction

With the continuous advancement of intelligent vehicle technologies, particularly in the field of active safety systems, the deployment of Advanced Driver-Assistance Systems (ADASs) has become increasingly widespread [1]. Maintaining driving safety—especially in complex and dynamic traffic environments—remains a fundamental requirement of intelligent vehicles. Among various active safety components, active collision avoidance systems play an irreplaceable role in preventing accidents by enabling vehicles to anticipate and avoid potential hazards in real time [2].
One of the most critical parameters affecting the performance of collision avoidance systems is the road surface adhesion coefficient, which directly reflects the frictional interaction between the tires and the road surface. This parameter determines the vehicle’s ability to accelerate, brake, and steer safely. An accurate and timely estimation of road adhesion allows the collision avoidance system to select an optimal control strategy that is adapted to the prevailing road conditions, thereby enhancing the safety of the vehicle and its occupants.
Various approaches have been proposed to estimate or identify the road surface adhesion coefficient. Jin-Oh [3] introduced a method that estimates adhesion based on the vehicle’s lateral dynamics response using a real-time identification algorithm fed by Differential GPS (DGPS) and gyroscopic sensors. While accurate, such methods are highly dependent on sensor availability and require high-precision positioning.
Šabanovič et al. [4] applied deep convolutional neural networks to classify six typical road surfaces, achieving an 88% recognition rate. However, their method mainly focuses on road surface type classification, and the indirect mapping from texture to adhesion coefficient may lack robustness in mixed or transitional road conditions. Similarly, Zhuo Yu et al. [5] utilized lidar reflection intensity combined with probabilistic fusion across multiple databases. This laser-based approach shows potential but can be significantly affected by environmental factors such as fog or dirt.
Image-based estimation methods, such as those using HSV color features and gray-level co-occurrence matrices [6,7], have been integrated with Hidden Markov Models (HMMs) to track road states. However, these methods are sensitive to ambient lighting and typically lack generalizability in low-visibility conditions. Junhui Lu [8] introduced a BP neural network that correlates environmental factors like solar radiation and pavement temperature with adhesion estimation. While useful in specific scenarios, its performance relies heavily on meteorological data accuracy.
Machine learning-based approaches, such as the SVM method proposed by Hongqiang Wu [9], have improved feature extraction and partial occlusion handling but still suffer from challenges in real-time applicability and generalization across variable environments. Additionally, Xianyao Ping et al. [10] enhanced adhesion estimation by introducing a strong tracking theory into the Unscented Kalman Filter (UKF), improving accuracy but increasing algorithmic complexity and parameter sensitivity. In terms of control strategy, Yuho Song [11] and Mingyue Yan [12] proposed predictive controllers and multi-objective fuzzy decision-making algorithms for active collision avoidance, focusing on high-level motion planning. However, they did not comprehensively consider the dynamic influence of real-time adhesion variation in their decision-making processes.
In response to the aforementioned limitations, this paper proposes an integrated framework that combines road adhesion coefficient estimation with a coordinated control strategy for active collision avoidance, featuring the following key innovations:
  • Accurate Adhesion Estimation Using SCKF: A real-time method for estimating the road surface adhesion coefficient is proposed based on the Square-Root Cubature Kalman Filter (SCKF), which demonstrates improved numerical stability and superior performance compared to traditional UKF-based approaches under nonlinear and non-Gaussian conditions.
  • Safety Distance Modeling with Adhesion Awareness: A dynamic safety distance model is established that explicitly considers the estimated road adhesion coefficient and the relative motion state of the leading vehicle, enabling more adaptive and context-aware collision risk assessment.
  • Novel Dual-Mode Control Strategy: A hybrid steering–braking cooperative collision avoidance controller is developed by integrating double PID control and fireworks algorithm-based optimization. This approach ensures real-time adaptability and effect control allocation under varying road conditions.
  • Integrated Decision Logic: A decision-making logic module is designed to determine the appropriate avoidance maneuver (steering, braking, or combined) based on both the adhesion coefficient and the vehicle’s dynamic state, thereby enhancing system robustness in complex scenarios.
In conclusion, this paper introduces advanced state estimation algorithms, establishes a dynamic safety model, designs a cooperative controller and an integrated decision-making mechanism, and constructs a highly precise, adaptable, and generalizable active collision avoidance system framework.

2. Vehicle Dynamic Modeling

2.1. Three-Degree-of-Freedom Vehicle Dynamics Model

This paper employs a three-degree-of-freedom vehicle dynamics model. Based on this model, the Square-Root Cubature Kalman Filter algorithm is applied to estimate the road surface adhesion coefficient. The force analysis of the vehicle is illustrated in Figure 1, and the following assumptions are made: the origin of the vehicle coordinate system coincides with the center of mass of the vehicle; the air resistance and rolling resistance during vehicle motion are neglected; the mechanical characteristics of the four tires are identical; the effect of the suspension is ignored, and the vehicle body is rigidly connected to the chassis; roll and yaw motions of the vehicle are not considered.
In Figure 1, CoG is the center of mass of the vehicle; F x f l , F x f r , F x r l , F x r r are the longitudinal forces of the left front wheel, right front wheel, left rear wheel, and right rear wheel, respectively; F y f l , F y f r , F y r l , F y r r are the lateral forces of the left front wheel, right front wheel, left rear wheel, and right rear wheel, respectively; L a , L b are the distances between the center of mass and the front and rear axes, respectively; and Bf, Br are the front and rear wheelbases, respectively.
The longitudinal equation of motion of the vehicle is
m a x = ( F x f l + F x f r ) c o s δ ( F y f l + F y f r ) s i n δ + F x r l + F x r r
where m is the mass of the vehicle, ax is the longitudinal acceleration of the vehicle, and δ is the front wheel’s angle of rotation
The lateral equation of motion of the vehicle is
m a y = ( F x f l + F x f r ) s i n δ ( F y f l + F y f r ) c o s δ + F y r l + F y r r
where ay is the lateral acceleration of the vehicle, while Fyrl and Fyrr are the lateral forces of the left and right rear wheels, respectively.
The yaw motion equation of the vehicle is
J ω ˙ = ( F x f r F x f l ) B f 2 c o s δ + ( F y f l F y f r ) B f 2 s i n δ + ( F x r r F x r l ) B r 2 + ( F x f l + F x f r ) L a s i n δ + ( F y f l + F y f r ) L a c o s δ ( F y r l + F y r r ) L b
where J is the rotational inertia of the vehicle around the z axis, ω is the angular velocity of the transverse pendulum, and Mz is the return torque.

2.2. Dugoff Tire Model

To accurately describe the relationship between the road adhesion coefficient and tire force, it is essential to select an appropriate tire model. Currently, tire models are primarily categorized into theoretical models, empirical models, and semi-empirical models. Among these, the theoretical models are derived by simplifying the physical model into a mathematical form, offering high accuracy. However, their main drawback lies in the complexity of the equations, which makes it difficult to meet real-time computational requirements. Empirical and semi-empirical models, on the other hand, are primarily based on extensive experimental tire data to fit expressions for various tire parameters. These models are generally more concise and sufficiently accurate compared to theoretical models. Commonly used models include the Magic Formula [13], the Dugoff model [14], and the UniTire model [15]. Considering the advantages of the Dugoff tire model—such as fewer parameters, lower computational demand, and ease of road adhesion coefficient separation—and taking into account the algorithm’s real-time requirements, the Dugoff tire model [16] was selected for tire force calculation. The corresponding tire force analysis is illustrated in Figure 2.
Expressions for the longitudinal force of the tire:
F x y = μ y F x y 0 = μ y F x y C x y s y 1 s y f ( l )
Expressions for the lateral force of the tire:
F y y = μ y F y y 0 = μ y F x y C y y t a n   α y 1 s y f ( l )
where f ( l ) = { 1 , l 1 l ( 2 l ) , l < 1 , l = ( 1 s i j ) ( 1 ε ν x C x i j 2 s i j 2 + C y i j 2 t a n 2 a i j ) 2 C x i j 2 s i j 2 + C y i j 2 t a n 2 a i j , where i = f and r represent the front and rear wheels, respectively; j = l and r represent the left and right wheels. respectively; μij is the road adhesion coefficient of each wheel; Cxij and Cyij are the longitudinal stiffness and lateral deviation stiffness of each wheel’s tire, respectively; sij is the tire slip rate of each wheel; αij is the side deviation angle of each wheel tire; ε is the velocity influencing factor; Fzij is the vertical load of the tires of each wheel; F x i j 0 , F y i j 0 are the normalized tire force of each wheel, ignoring the influence of the road adhesion coefficient, which is conducive to algorithm programming; f(l) is the model correction factor; and l is the characteristic parameter of tire slip.
The slip rate is calculated as follows:
s i j = { ν i j ω i j R ν i j ,   b r a k i n g ω i j R ν i j ν i j ,   d r i v e
where vij is the longitudinal velocity of each wheel, ωij is the angular velocity of each wheel, and R is the effective rolling radius of the wheel.
The formula for calculating the wheels’ center velocity is
v c f l = ( v x + B f ω ˙ f l / 2 ) cos δ + ( v y + L a ω ˙ f l ) sin δ v c f l = ( v x B f ω ˙ f r / 2 ) cos δ + ( v y + L a ω ˙ f r ) sin δ v c r l = v x + B r ω ˙ r l / 2 v c r r = v x B r ω ˙ r r / 2
where, vcfl, vcfr, vcrl, and vcrr are the velocities at the center of the left front wheel, the right front wheel, the left rear wheel, and the right rear wheel, respectively; ωfl, ωfr, ωrl, and ωrr are the angular velocities of the left front wheel, the right front wheel, the left rear wheel, and the right rear wheel, respectively; and vy is the lateral speed of the vehicle.
The formula for calculating the deviation angle of a tire is
α f l = δ + arctan v y + L a ω ˙ f l v x + B f ω ˙ f l / 2 α f r = δ + arctan v y + L a ω ˙ f r v x B f ω ˙ f r / 2 α r l = arctan v y L a ω ˙ r l v x + B r ω ˙ r l / 2 α r r = arctan v y L a ω ˙ r r v x B r ω ˙ r r / 2
The formula for calculating the vertical load of the wheel is
F z f l = m g L b 2 L m a x h g 2 L + m a y h g L b L B f F z f r = m g L b 2 L m a x h g 2 L m a y h g L b L B f F z r l = m g L b 2 L + m a x h g 2 L m a y h g L a L B r F z r r = m g L b 2 L + m a x h g 2 L + m a y h g L a L B r
where L = La + Lb is the wheelbase, g is the acceleration due to gravity, and hg is the height of the center of mass.

3. Design of Pavement Adhesion Coefficient Estimator

3.1. Square-Root Volume Kalman Filter Algorithm

The Cubature Kalman Filter (CKF) algorithm is a novel nonlinear Gaussian filtering method introduced by Canadian researchers in 2009 [17]. It has been widely applied in fields such as aerospace [18], target tracking [19,20], and battery state-of-charge (SOC) estimation [21]. The CKF selects cubature points based on the third-order spherical–radial cubature rule and achieves high computational accuracy. Compared with the Unscented Kalman Filter (UKF), the cubature points in the CKF are symmetrically distributed in a lower-dimensional space, and all points share equal weights, eliminating the need for prior parameter tuning. However, due to numerical rounding errors and other computational factors, the CKF covariance matrix may lose positive definiteness, leading to reduced observer stability.
To address the limitations of the Cubature Kalman Filter algorithm in state parameter estimation, this paper proposes the square-root cubature Kalman filtering algorithm, which avoids the non-negative definiteness of the matrix and the instability of the observer caused by the square of the covariance matrix of the CKF by employing orthogonal triangular decomposition and enhances both estimation accuracy and algorithmic robustness. The estimation flowchart is illustrated in Figure 3.
The parameter variables of the system are determined as x = [μfl,μfr,μrl,μrr]T, according to Equations (1)–(3) of the vehicle dynamics. Define the observed quantity of the system as y = [ax,ay, ω ˙ ]T and the input quantity of the system as u = [δ, F x i j 0 , F y i j 0 ]T. The specific estimation process is as follows:
Step 1: For a general nonlinear system, the state-space equation can be written as follows:
{ x ˙ ( t ) = f ( x ( t ) , u ( t ) ) + w ( t ) y ( t ) = h ( x ( t ) , u ( t ) ) + v ( t )
where f(x(t), u(t)) and h(x(t), u(t)) are the equation of state and measurement equation of the estimated system, respectively; w(t) is the process noise; and v(t) is the measurement noise.
Step 2: The state and observation equations of the estimator can be expressed as follows:
x ˙ ( t ) = [ 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 ] [ μ f l μ f r μ r l μ r r ] + w ( t )
y ( t ) = [ h ( 1,1 )   h ( 1 , 2 )   h ( 1,3 )   h ( 1,4 ) h ( 2,1 )   h ( 2,2 )   h ( 2,3 )   h ( 2,4 ) h ( 3,1 )   h ( 3,2 )   h ( 3,3 )   h ( 3,4 ) ] [ μ f l μ f r μ r l μ r r ] + v ( t )
where h ( 1,1 ) = F x f l 0 c o s δ F y f l 0 s i n δ m , h ( 1 , 2 ) = F x f r 0 c o s δ F y f r 0 s i n δ m , h ( 1,3 ) = F   x r l 0 m ,   h ( 1,4 ) = F   x r r 0 m , h ( 2,1 ) = F x f l 0 s i n δ + F y f l 0 c o s δ m , h ( 2,2 ) = F x f l 0 s i n δ + F y f l 0 c o s δ m , h ( 2,3 ) = F y r l 0 m , h ( 2,4 ) = F y r r 0 m , h ( 3,1 ) = ( F y f l 0 s i n δ F x f l 0 c o s δ ) B f / 2 + ( F x f l 0 s i n δ + F y f l 0 c o s δ ) L f J , h ( 3,2 ) = ( F x f r 0 c o s δ F y f r 0 s i n δ ) B f / 2 + ( F x f r 0 s i n δ + F y f r 0 c o s δ ) L f J , h ( 3,3 ) = F x r l 0 B r / 2 + F y r l 0 L r J , h ( 3,4 ) = F x r r 0 B r / 2 F y r r 0 L r J .
Step 3: The Singular Value Decomposition (SVD) method is used to decompose the state volume error covariance matrix:
G k 1 | k 1 = s v d ( P k 1 | k 1 )
where Gk − 1|k − 1 is the state error covariance matrix, Pk − 1|k − 1 is the state quantity error covariance matrix at the (k − 1) moment, and svd( ) is the matrix decomposition function.
Step 4: Calculate the volume point:
x i , k 1 = G k 1 | k 1 ξ i + x ^ k 1   i = 1 , 2 , 2 n
where x ^ k − 1 is the predicted value of the state quantity at the moment (k − 1), n is the dimension of the state quantity, ξi =  B is the cubature point weight matrix, and B = [In × n − In × n].
Step 5: Calculate the volume point after iteration of the equation of state:
x i , k | k 1 * = f ( x i , k 1 , u )
Step 6: State One Step Prediction:
x ^ k | k 1 = 1 2 n i = 1 2 n x i , k | k 1 *
where x ^ k|k − 1 is the state prediction at moment k.
Step 7: Calculate the square root of the error covariance matrix of the predicted values of the state quantities:
G k | k 1 = q r ( [ x k | k 1 * , J Q , k | k 1 ] )
where x k | k l * = 1 2 n [ ( x i , k | k 1 * x ^ k | k 1 ) ] is the state-volume-weighted center matrix, JQ,k|k − 1 = chol(Qk) is the square-root factorization of Qk, Qk is the observer process noise covariance matrix, chol( ) is the matrix Cholesky decomposition operation, and qr( ) is the orthogonal triangular decomposition operation of the matrix.
Step 8: Calculate the updated volume points:
x i , k | k 1 = G k | k 1 ξ i + x ^ k | k 1
Step 9: Propagate the volume points by substituting them into the volume equation:
y i , k | k 1 = h ( x i , k | k 1 , u )
y ^ k | k 1 = 1 2 n i = 1 2 n y i , k | k 1
where y ^ k|k− 1 is the estimated value of the observation at moment k. The following is an example of the estimation of the observation at moment k:
Step 10: Calculate the square root of the error covariance matrix of the predicted values of the observations:
G z z , k | k 1 = q r ( [ y k | k 1 , J R , k ] )
where y k | k 1 = 1 2 n [ ( y i , k | k 1 y ^ k | k 1 ) ] is the observation-weighted center matrix, JR,k|k − 1 = chol(Rk) is the square-root factorization of Rk, and Rk is the observer measurement noise covariance matrix.
Step 11: Calculate the mutual covariance matrix:
P x y , k | k 1 = x k | k 1 y k | k 1 T
where x k | k 1 = 1 2 n [ ( x i , k | k 1 x ^ k | k 1 ) ] .
Step 12: Calculate the filter gain matrix:
K k = P x y , k | k 1 ( G z z , k | k 1 G z z , k | k 1 T ) 1
Step 13: Update the square-root factor of the error covariance matrix:
x ^ k = x ^ k | k 1 + K k ( y y ^ k | k 1 )
Step 14: Update the square-root factor of the error covariance matrix:
G k = q r ( [ x k | k 1 K k y k | k 1 , K k J R , k | k 1 ] )
According to the settings of the SCKF algorithm used in this paper, Table 1 summarizes the key parameters and their meanings. These parameters were selected based on the vehicle dynamics characteristics and sensor accuracy, which not only ensures the estimation accuracy but also improves the numerical stability.

3.2. Model for Estimating Pavement Adhesion Coefficient

In order to verify the effectiveness of the proposed algorithm in this section, the CarSim/Simulink co-simulation platform was employed. The CKF algorithm and SCKF algorithm were implemented to estimate the pavement adhesion coefficient, and the estimated values of the algorithms were compared with the reference values provided by CarSim, so as to verify the accuracy and validity of the SCKF algorithm. The estimation flowchart is illustrated in Figure 4.
In CarSim, the initial speed of the vehicle was set to 80 km/h, the throttle opening was 0, the transmission was in neutral, the brake wheel cylinder pressure was 0.3 MPa, the road surface adhesion coefficient setting was set to 0.8 and 0.4, and the simulation time was 10 s. Simulation experiments were carried out, and the simulation results are presented in Figure 5 and Figure 6.
To quantitatively assess the accuracy of the estimation algorithms, the root-mean-square error (RMSE) was employed to measure the deviation between the estimated values and the actual values, as presented in Table 2. By comparing the simulation curves, it can be observed that both the Cubature Kalman Filter (CKF) algorithm and the Square-Root Cubature Kalman Filter (SCKF) algorithm exhibit a tendency to converge towards the standard values. In comparison with the CKF algorithm, the SCKF algorithm demonstrates higher convergence accuracy. This is because the SCKF algorithm utilizes the orthogonal triangular decomposition method to ensure the positive definiteness of the covariance matrix, whereas the CKF algorithm’s use of square-root decomposition results in a negative-definite covariance matrix.

4. Establishment of Safe Distance Model

4.1. Vertical Safe Distance Model

As shown in Figure 7, the complete braking process consists of the driver’s reaction time τ1, the braking mechanism’s action time τ2 (where τ2′ and τ2′′ represent the time required to eliminate the braking clearance and the time for the braking pressure to increase, respectively), the continuous braking time τ3, and the time for the braking to be canceled τ4.
Let the intelligent vehicle and the front vehicle be traveling in the same lane, in the safe braking distance model shown in Figure 8. In the figure, v0 and vxfront are the initial speeds of the intelligent car and the front car, respectively; dbr is the distance between the two cars when they are not braked; S is the distance traveled by the intelligent car when it is braked; Sfront is the distance traveled by the front car when it is braked; and dsafe is the minimum safe distance.
Depending on the different states of motion of the front vehicle, the safe distances between the intelligent vehicle and the front vehicle are as follows:
Critical safe distance for stationary working conditions of the vehicle in front:
d b r = v 0 ( τ 2 + τ 2 2 ) + v 0 2 2 a b m a x + d s a f e
Critical safe distance at uniform speed of the vehicle in front:
d b r = ( v 0 v x f r o n t ) × ( τ 2 + τ 2 2 ) + ( v 0 ν x f r o n t ) 2 2 a b m a x + d s a f e
Critical safe distance under emergency braking conditions of the vehicle in front:
d b r = ( ν 0 ν x f r o n t ) × ( τ 2 + τ 2 2 ) + ν 0 2 2 a b m a x + ν x f r o n t 2 2 a x f r o n t + d s u f e
where axfront is the braking deceleration of the front vehicle; abmax is the maximum braking deceleration of the intelligent vehicle, which is related to the road surface adhesion coefficient, which is effectively estimated as detailed in the previous section; τ1 is the reaction time of the driver of the intelligent vehicle; and τ2′ and τ2″ are the time required for the brake to start acting and the time for the brake force to continue acting, respectively.

4.2. Steering Safe Distance Model

The potential collision types that may occur during lane changing are front corner collisions, mid-vehicle collisions, and rear corner collisions, as illustrated in Figure 9.
Assuming that the vehicle performs a lane change for collision avoidance in an adjacent lane without interference from other vehicles, the rear corner point is considered to be the last possible collision point based on a fifth-degree polynomial trajectory planning method. To ensure collision avoidance, it is sufficient to guarantee that the intelligent vehicle’s right rear corner point, relative to the vehicle’s center of mass, maintains a distance greater than half of the front vehicle’s lateral width. This ensures that all parts of the following vehicle will not collide with the front vehicle. The collision avoidance schematic is illustrated in Figure 10.
In Figure 10, O is the center of mass of the smart vehicle; α and γ are the angles between the vehicle axis and the line connecting the vehicle’s center of mass to the vehicle’s right rear and right front corner points, respectively; tc is the moment of critical collision; and θ is the vehicle’s heading angle.
The distance LOE between the center of mass of the intelligent vehicle and the outer edge of the front vehicle is calculated as follows:
L O E = ( L r r 2 + ( W r / 2 ) 2 · cos ( π / 2 θ a )
where Lrr is the distance from the center of mass of the intelligent vehicle to the rear edge of the front vehicle, and Wr is the width of the intelligent vehicle.
When te/2, vy reaches its maximum value, θ also reaches its maximum value. The calculation formula is
θ m a x = arctan 15 y d 8 v x t e
In order to prevent the rear vehicle from colliding with the leading vehicle, the intelligent vehicle should meet the following requirements in the lateral direction:
W f 2 = y e [ 10 ( t c t e ) 3 15 ( t c t e ) 4 + 6 ( t c t e ) 5 ] ( L r r 2 + ( W r 2 ) 2 · cos ( π 2 θ m a x a )
where Wf is the width of the front vehicle.
The critical collision time tc can be obtained by solving Equation (31), so the safe distance under the conditions of stationary front vehicle, uniform speed of front vehicle, and braking condition of front vehicle can be obtained, which is calculated as follows:
Corresponding critical safety distance for steering collision avoidance under stationary conditions of the front vehicle dst_steer:
d s t _ s t e e r = v x t c + L o c cos ( γ θ ( t c ) ) L f f + d safe
The corresponding steering collision avoidance critical safety distance dcon_steer when the front vehicle is traveling at a constant speed with speed vfront:
d c o n _ s t e e r = ( v x v f r o n t ) t c + L o c cos ( γ θ ( t c ) ) L f f + d safe
When the front vehicle is decelerating with the maximum braking deceleration afmax, the corresponding critical safe distance for steering to avoid collision is dbr_steer:
d b r , s t e e r = ( ν x ν f r o n t + a f m a x t c 2 ) t c + L o c cos ( γ θ ( t c ) ) L f f + d safe

5. Steering Brake Joint Collision Avoidance Controller Design

5.1. Determination of the Domain of the Steering and Braking Distribution Coefficients

Brake steering cooperative control is different from the single control mode. During the collision avoidance process, braking and steering are coupled with each other, and the longitudinal force and lateral force of the tire should meet the adhesion condition:
F x 2 + F y 2 μ F z
The friction circle is shown in Figure 11. The right half of the axis in the figure represents a right turn, the left half represents a left turn, the upper half represents drive control, and the lower half represents brake control. As the steering wheel angle and braking intensity continuously increase, the longitudinal force and lateral force acting on the tire also increase [22].
From the formula, the relationship between the longitudinal acceleration and the lateral acceleration is obtained:
( λ a x m a x ) 2 + ( γ a y m a x ) 2 μ g
where λ represents the braking distribution coefficient, and γ represents the steering distribution coefficient.
The selection of braking and steering distribution coefficients plays a critical role in the collision avoidance effect. The selection principle for the domain of braking and steering distribution coefficients is as follows:
(1)
Domain of the Braking Distribution Coefficient:
The braking system applies braking based on the maximum frictional force that the ground can provide, and its domain is [0, 1].
(2)
Definition Domain of the Distribution Coefficient:
This paper draws on the research results of Nathaniel [23], as shown in Table 3, to classify the lateral acceleration and thereby determine the domain of the definition of the steering distribution coefficient.
When the vehicle is traveling at a low speed and the road adhesion coefficient is high, a smaller distribution coefficient should be selected; otherwise, a larger steering distribution coefficient should be chosen. The range of maximum lateral acceleration for different road surfaces is presented in Table 4.

5.2. Brake–Steering Coefficient Allocation Based on the Fireworks Algorithm

In this study, the fireworks algorithm (FWA) is not used as a generic optimization tool but is tailored for brake–steering control allocation to satisfy the constraints of the friction circle and vehicle stability.
(1)
Search Space Definition:
The search variables are a two-dimensional vector (λ, γ), where λ is the braking distribution coefficient and γ is the steering distribution coefficient. Their ranges are determined according to the friction circle conditions, Equations (35) and (36), and stability boundaries, ensuring that the allocation does not cause the tires’ longitudinal and lateral forces to exceed limits.
(2)
Fitness Function Construction:
To balance collision avoidance performance and vehicle stability, the fitness function Equation (44) is constructed as a weighted sum of the normalized braking deceleration Equation (41), safety distance Equation (42), and lane-change time Equation (43). The weights are selected according to a safety-first principle.
(3)
Search Strategy:
Local Refinement: High-fitness solutions generate more sparks within a small search radius, enabling fine-tuning of the allocation coefficients;
Global Exploration: Low-fitness solutions search over a larger radius, increasing the probability of escaping local optima;
Constraint Repair: Each newly generated solution is projected back to the feasible domain to satisfy physical and safety constraints.
(4)
Application Results:
Through iterative optimization, the FWA can quickly converge to the optimal (λ, γ), achieving dynamic optimal allocation of braking and steering adhesion utilization. Under different adhesion conditions, this significantly shortens the collision avoidance distance and improves the vehicle’s attitude stability.
The framework of the fireworks algorithm is mainly composed of the following four parts: the explosion operator, variation operation, mapping rule, and selection strategy [24]; the flowchart composing the framework of the fireworks algorithm is shown in Figure 12.
The longitudinal acceleration based on the brake distribution factor is
a x m = λ a x m a x
where λ denotes the brake distribution coefficient.
The lateral acceleration based on the steering distribution coefficient is
a y = 2 π y e t e _ c o m b i n e s i n ( 2 π t t e _ c o m b i n e )
where the lane-change time based on the steering allocation factor is
t e _ c o m b i n e = 2 π y e γ μ g
where γ denotes the steering distribution factor.

5.3. Fireworks Algorithm Evaluation Function Establishment

Normalization is carried out by polarization:
x n = x n x n min x n max x n min
where xnmax denotes the maximum value of the variable and xnmin denotes the minimum value of the variable.
The normalized sum of braking deceleration speed, safe braking distance, and lane-change time is selected as the value of the fitness function, which is calculated as follows:
Brake deceleration axm′ normalization formula:
a x m = λ λ m i n λ m a x λ m i n
Safety distance d0′ normalization formula:
d 0 = λ m i n λ m a x λ λ m i n λ λ m a x λ λ m i n
Transit time te′ normalization formula:
t e = γ min γ max γ γ min γ γ max γ γ min
In summary, the fitness function is
F = a x + d 0 + t e

5.4. PID-Based Steering and Braking Controller

After obtaining the optimal allocation coefficients (λ, γ), PID controllers are used to track the desired longitudinal and lateral accelerations.
(1)
Control Objectives:
Brake Controller Input: The difference between the desired longitudinal acceleration and the current actual longitudinal acceleration (Equation (45));
Steering Controller Input: The difference between the desired lateral acceleration and the current actual lateral acceleration (Equation (46)).
(2)
Tuning Procedure:
Initial Estimation: The feasible range of PID gains is estimated based on a linearized vehicle dynamics model;
Ziegler–Nichols Coarse Tuning: The ultimate gain Ku and ultimate oscillation period Tu are measured to calculate the initial parameters;
Performance Optimization: Parameters are fine-tuned according to the ITAE criterion, maximum overshoot, and actuator smoothness;
Global Optimization with FWA: Within the stable domain of (λ, γ), the fireworks algorithm further optimizes the PID parameters to improve tracking accuracy and control smoothness.
(3)
Execution:
The PID outputs for braking and steering are converted into brake pressure and steering angle inputs via the inverse braking system model and inverse steering system model (Equations (47) and (48), respectively), thereby implementing coordinated brake–steering collision avoidance control.
The input to the brake controller is the difference between the desired longitudinal acceleration λ a x and the actual longitudinal acceleration a x of the vehicle at the current moment; that is,
e x ( t ) = λ a x ( t ) a x ( t )
The input to the steering controller is the difference between the desired lateral acceleration γ a y and the actual lateral acceleration a y of the vehicle at the current moment; that is,
e y ( t ) = γ a y ( t ) a y ( t )
The expression of the PID algorithm in the continuous time domain is
u ( t ) = K p [ e ( t ) + 1 T i 0 t e ( t ) d t + T d d e ( t ) d t ]
k p = K p ,   k i = K p T i ,   k d = K p T D
where Kp is the proportional gain, Ti is the differential time constant, Td is the integral time constant, kp is the proportional coefficient, ki is the integral coefficient, and kd is the differential coefficient.

6. Simulation Verification

6.1. Basic Software Parameter Settings

In this paper, the Audi A8, which comes with CarSim, is used for co-simulation, and the specific simulation parameters are shown in Table 5.

6.2. Combined Braking and Steering Obstacle Avoidance Conditions Under High-Adhesion Road Surfaces

According to the friction circle and vehicle stability constraints to determine the road surface adhesion coefficient of 0.8, the conditions under the brake distribution coefficient stability domain are [0.12, 0.87], while those under the steering distribution coefficient stability domain are [0.23, 0.85]. Through the fireworks algorithm for the brake distribution coefficient and steering distribution coefficient optimization, after 35 generations, the algorithm adaptability value is maintained at 0.759. The adaptability of the change is shown in Figure 13. At this time, the brake allocation coefficient and steering allocation coefficient are 0.16 and 0.75, respectively.
We set the speed of this vehicle to 72 km/h, the initial distance between the two vehicles to 60 m, the speed of the front vehicle to 72 km/h, the two vehicles traveling in the same direction, the front vehicle starting braking after 1 s, and the braking deceleration to 5 m/s2; the simulation results are shown in Figure 14. From Figure 14a–d, it can be seen that the vehicle starts collision avoidance from 89.2 m; at this time, the distance between the two vehicles is much smaller than the same conditions of steering collision avoidance distance between the two vehicles, lateral acceleration is controlled in the range of (−6, 6) m/s2, the maximum brake deceleration is 6.82 m/s2, and the vehicle’s traverse angle is controlled in the range of (−2°, 13.7°). In summary, the vehicle is able to track the desired lateral acceleration to complete the collision avoidance maneuver.

6.3. Combined Braking and Steering Obstacle Avoidance Conditions Under Medium-Adhesion Road Surfaces

According to the friction circle and vehicle stability constraints to determine the road surface adhesion coefficient of 0.4, the conditions under the brake distribution coefficient stability domain are [0.12, 0.87], while those under the steering distribution coefficient stability domain are [0.23, 0.85]. Through the fireworks algorithm for the brake distribution coefficient and steering distribution coefficient optimization, after 95 generations, the algorithm adaptability value is maintained at 0.503. The adaptability of the change is shown in Figure 15. At this time, the brake allocation coefficient and steering allocation coefficient are 0.16 and 0.81, respectively.
We set the speed of this vehicle to 72 km/h, the initial distance between the two vehicles to 40 m, the speed of the front vehicle to 72 km/h, the two vehicles traveling in the same direction, the front vehicle starting braking after 1 s, and the braking deceleration to 5 m/s2; the simulation results are shown in Figure 16. From Figure 16a–d, it can be seen that the vehicle starts collision avoidance from 80.1 m; at this time, the distance between the two vehicles is much smaller than the same conditions of steering collision avoidance distance between the two vehicles, lateral acceleration is controlled in the range of (−4, 4) m/s2, the maximum brake deceleration is 3.31 m/s2, the vehicle’s traverse angle is controlled in the range of (−2°, 8°). In summary, the vehicle is able to track the desired lateral acceleration to complete the collision avoidance maneuver.

7. Conclusions

This paper addresses the filter divergence problem caused by the asymmetry of the covariance matrix in existing pavement adhesion coefficient estimators, and it proposes an estimator based on the square-root cubature Kalman filtering algorithm (SCKF). The simulation results demonstrate that the proposed SCKF method significantly outperforms the traditional Cubature Kalman Filter (CKF) across different tires and road adhesion coefficients. Specifically, under low-adhesion conditions (μ = 0.4), the SCKF algorithm reduces the RMSE of each wheel by up to 92.7%, while under higher-adhesion conditions (μ = 0.8) the improvement rate ranges from 76.1% to 86.4%. These results confirm the superior estimation accuracy and filtering stability of the SCKF algorithm, effectively enhancing the safety and reliability of dynamic vehicle control.
Regarding the safe distance model and lane-change path planning, this study developed a safe distance model that accounts for various lead vehicle motion states and designs lane-change path functions based on fifth-degree polynomial trajectory planning. Furthermore, a decision logic for an active collision avoidance system was established, enabling the vehicle to make reasonable and timely collision avoidance maneuvers according to real-time traffic scenarios, thereby improving the proactivity and intelligence of collision avoidance.
To overcome the limitations of steering-only collision avoidance strategies under extreme conditions, a joint steering–braking collision avoidance strategy is proposed. Steering and braking allocation coefficients are optimized using the fireworks algorithm, and desired longitudinal and lateral accelerations are tracked via PID control to achieve closed-loop control. The simulation results verify that this approach initiates collision avoidance earlier and effectively regulates lateral acceleration and yaw angle, thereby enhancing the safety and stability of collision avoidance.
Future work will focus on applying the proposed algorithms to more complex road scenarios and multi-vehicle cooperative collision avoidance. Integration with deep learning methods will be explored to improve real-time performance and robustness. Additionally, implementation and testing on actual vehicle hardware platforms will be pursued to facilitate the industrialization of active safety technologies.

Author Contributions

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

Funding

This research was funded by the Shandong Provincial Higher School Youth Innovation Technology Project of China (Grant No. 2021KJ039), Science and Technology Project (Grant No. 2022B107) of Department of Transport of Shandong Province.

Data Availability Statement

The original contributions presented in this study are included in the article. Further inquiries can be directed to the corresponding author.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Yang, X. Research on the Control Strategy of Automobile Active Collision Avoidance System. Master’s Thesis, Chongqing University of Technology, Chongqing, China, 2019. [Google Scholar]
  2. Xu, H. Research on Vehicle Active Collision Avoidance Considering Road Attachment Coefficient. Master’s Thesis, Chang’an University, Xi’an, China, 2023. [Google Scholar]
  3. Jin-Oh, H.; Rajamani, R.; Alexander, L. Gps-based real-time identification of tire-road friction coefficient. IEEE Trans. Control. Syst. Technol. 2002, 10, 331–343. [Google Scholar] [CrossRef]
  4. Šabanovič, E.; Žuraulis, V.; Prentkovskis, O.; Skrickij, V. Identification of road-surface type using deep neural networks for friction coefficient estimation. Sensors 2020, 20, 612. [Google Scholar] [CrossRef] [PubMed]
  5. Yu, Z.; Zeng, D.; Xiong, L.; Zhang, P. Estimation of Road Adhesion Coefficient for Unmanned Vehicles Based on Lidar. J. Huazhong Univ. Sci. Technol. (Nat. Sci. Ed.) 2019, 47, 124–127. [Google Scholar]
  6. Fan, X. Research on Prediction of Front Road-Tire Adhesion Characteristics Based on HMM. Master’s Thesis, Jiangsu University, Zhenjiang, China, 2018. [Google Scholar]
  7. Yuan, C.; Zhang, H.; He, Y.; Shen, J.; Chen, L. Identification of Frontal Attachment Coefficient Based on Image Features and HMM. J. Jiangsu Univ. (Nat. Sci. Ed.) 2022, 43, 373–380+393. [Google Scholar]
  8. Lu, J.; Wang, J.; Li, K.; Lian, X. Method for Road Condition Recognition Based on Road Temperature and Solar Radiation Intensity. Trans. Chin. Soc. Agric. Mach. 2010, 41, 21–23+11. [Google Scholar]
  9. Wu, H. Research on Road Condition Video Image Recognition Technology Based on Support Vector Machine. Master’s Thesis, Beijing Jiaotong University, Beijing, China, 2017. [Google Scholar]
  10. Ping, X.; Li, L.; Cheng, S.; Wang, H. Research on the identification of road surface adhesion coefficient for four-wheel independent drive vehicles under multiple working conditions. J. Mech. Eng. 2019, 55, 80–92. [Google Scholar]
  11. Song, Y.; Huh, K. Driving and steering collision avoidance system of autonomous vehicle with model predictive control based on non-convex optimization. Adv. Mech. Eng. 2021, 13, 16878140211027669. [Google Scholar] [CrossRef]
  12. Yan, M.; Wei, M.; Wang, K.; Zhao, W.; Wang, Y.; Zhang, F. Cooperative collision avoidance control of steering and braking based on function allocation and multi-objective fuzzy decision-making. J. Chongqing Univ. Technol. (Nat. Sci.) 2018, 32, 63–71. [Google Scholar]
  13. Pacejka, H.B.; Bakker, E. The magic formula tyre model. Veh. Syst. Dyn. 1992, 21, 1–18. [Google Scholar] [CrossRef]
  14. Dugoff, P.H.; Fancher, S.P.; Segel, L. An analysis of tire traction priperties and their infuluence on vehicle dynamic performance. SAE Trans. 1970, 79, 1219–1243. [Google Scholar]
  15. Guo, K.; Lu, D. Unitire: Unified tire model for vehicle dynamic simulation. Veh. Syst. Dyn. 2007, 45 (Suppl. S1), 79–99. [Google Scholar] [CrossRef]
  16. Li, X. Research on Vehicle Anti Collision Control Algorithm Based on Road Adhesion Coefficient. Master’s Thesis, Hefei University of Technology, Hefei, China, 2018. [Google Scholar]
  17. Arasaratnam, I.; Haykin, S. Cubature kalman filters. IEEE Trans. Autom. Control. 2009, 54, 1254–1269. [Google Scholar] [CrossRef]
  18. Xiao, F.; Li, Y.F.; Wang, B.; Seng, Q.H.; Wu, F. Volumetric particle filtering single-star target tracking algorithm under double constraints. Tactical Missile Technol. 2023, 5, 131–141. [Google Scholar]
  19. Zhang, L. Multi-ram class target tracking based on stckf-cphd algorithm. Chin. J. Inert. Technol. 2023, 31, 510–515. [Google Scholar]
  20. Wu, H.; Chen, S.; Yang, B.; Chen, K. Robust volumetric Kalman filter target tracking algorithm based on generalized m estimation. Phys. Lett. 2015, 64, 218401. [Google Scholar]
  21. Zheng, T.; Zhang, L.; Hou, Y.C.; Chen, W. Adaptive ckf-based soc estimation for aging lithium batteries. Energy Storage Sci. Technol. 2020, 9, 1193–1199. [Google Scholar]
  22. Yu, Z.; Jiang, W.; Zhang, L. Torque Distribution Control for Four-wheel Hub Motor Driven Electric Vehicles. J. Tongji Univ. (Nat. Sci. Ed.) 2008, 8, 1115–1119. [Google Scholar]
  23. Sledge, N.H. An Investigation of Vehicle Critical Speed and Its Influence on Lane-Change Trajectories; The University of Texas at Austin: Austin, TX, USA, 1997. [Google Scholar]
  24. Song, X.; Ren, X. Research on self-learning fuzzy control strategy of pure electric vehicle fireworks algorithm. Mech. Des. Manuf. 2018, 4, 108–110+114. [Google Scholar]
Figure 1. Three-degree-of-freedom vehicle dynamics model.
Figure 1. Three-degree-of-freedom vehicle dynamics model.
Wevj 16 00489 g001
Figure 2. Dugoff tire model.
Figure 2. Dugoff tire model.
Wevj 16 00489 g002
Figure 3. Flowchart of SCKF algorithm.
Figure 3. Flowchart of SCKF algorithm.
Wevj 16 00489 g003
Figure 4. Flowchart for estimation of pavement adhesion coefficient. The arrows in the diagram represent the direction of the relevant variables.
Figure 4. Flowchart for estimation of pavement adhesion coefficient. The arrows in the diagram represent the direction of the relevant variables.
Wevj 16 00489 g004
Figure 5. Simulation verification of high-adhesion-coefficient road surface: (a) left front wheel; (b) right front wheel; (c) left rear wheel; (d) right rear wheel.
Figure 5. Simulation verification of high-adhesion-coefficient road surface: (a) left front wheel; (b) right front wheel; (c) left rear wheel; (d) right rear wheel.
Wevj 16 00489 g005aWevj 16 00489 g005b
Figure 6. Simulation verification of medium-adhesion-coefficient road surface: (a) left front wheel; (b) right front wheel; (c) left rear wheel; (d) right rear wheel.
Figure 6. Simulation verification of medium-adhesion-coefficient road surface: (a) left front wheel; (b) right front wheel; (c) left rear wheel; (d) right rear wheel.
Wevj 16 00489 g006
Figure 7. The process of vehicle braking. “a” represents normal vehicle operation without braking; “b” represents initiation of brake pedal input before braking force is generated; “c” represents the onset of braking system response, reflecting the delay between pedal input and deceleration; “d” represents a marked increase in braking deceleration as transmission delay diminishes; “e” represents attainment of maximum (stable) braking deceleration Fp and pedal force ap, indicating the stable braking phase; “f” represents the onset of brake pedal release, with deceleration beginning to decrease; and “g” represents the return of braking force to zero, marking the end of the braking process as the vehicle resumes coasting.
Figure 7. The process of vehicle braking. “a” represents normal vehicle operation without braking; “b” represents initiation of brake pedal input before braking force is generated; “c” represents the onset of braking system response, reflecting the delay between pedal input and deceleration; “d” represents a marked increase in braking deceleration as transmission delay diminishes; “e” represents attainment of maximum (stable) braking deceleration Fp and pedal force ap, indicating the stable braking phase; “f” represents the onset of brake pedal release, with deceleration beginning to decrease; and “g” represents the return of braking force to zero, marking the end of the braking process as the vehicle resumes coasting.
Wevj 16 00489 g007
Figure 8. Schematic diagram of the safe distance model.
Figure 8. Schematic diagram of the safe distance model.
Wevj 16 00489 g008
Figure 9. Schematic diagram of lane-changing collision mode.
Figure 9. Schematic diagram of lane-changing collision mode.
Wevj 16 00489 g009
Figure 10. Schematic diagram of intelligent vehicle safety collision avoidance.
Figure 10. Schematic diagram of intelligent vehicle safety collision avoidance.
Wevj 16 00489 g010
Figure 11. Schematic diagram of friction circle.
Figure 11. Schematic diagram of friction circle.
Wevj 16 00489 g011
Figure 12. Flowchart of the fireworks algorithm.
Figure 12. Flowchart of the fireworks algorithm.
Wevj 16 00489 g012
Figure 13. Variation of μ = 0.8 fireworks algorithm for finding an optimal solution.
Figure 13. Variation of μ = 0.8 fireworks algorithm for finding an optimal solution.
Wevj 16 00489 g013
Figure 14. Comparison of joint collision avoidance parameters at μ = 0.8: (a) comparison of tracking trajectories; (b) comparison of lateral acceleration; (c) longitudinal acceleration; (d) yaw angle.
Figure 14. Comparison of joint collision avoidance parameters at μ = 0.8: (a) comparison of tracking trajectories; (b) comparison of lateral acceleration; (c) longitudinal acceleration; (d) yaw angle.
Wevj 16 00489 g014
Figure 15. Variation of μ = 0.4 fireworks algorithm for finding an optimal solution.
Figure 15. Variation of μ = 0.4 fireworks algorithm for finding an optimal solution.
Wevj 16 00489 g015
Figure 16. Comparison of joint collision avoidance parameters at μ = 0.4: (a) comparison of tracking trajectories; (b) comparison of lateral acceleration; (c) longitudinal acceleration; (d) yaw angle.
Figure 16. Comparison of joint collision avoidance parameters at μ = 0.4: (a) comparison of tracking trajectories; (b) comparison of lateral acceleration; (c) longitudinal acceleration; (d) yaw angle.
Wevj 16 00489 g016
Table 1. Summary of key parameters of SCKF.
Table 1. Summary of key parameters of SCKF.
Name of ParameterValue/SettingNotes
State vector x[μfl,μfr,μrl,μrr]Four-wheel road adhesion coefficient
Observation variable y[ax,ay,ω]Longitudinal acceleration, lateral acceleration, yaw angular velocity
State dimension n4Determine the number of volume points
Process noise covariance QkModel calibrationIndicating modeling errors and disturbances
Measurement noise covariance RkSensor calibrationIndicates the measurement accuracy of the sensor
Decomposition methodSVD + QR + CholeskyEnsuring the positive definiteness of the covariance and numerical stability indicates the measurement accuracy of the sensor
Update step size0.01 sSynchronized with vehicle dynamics simulation
Table 2. RMSE values for different road adhesion coefficients.
Table 2. RMSE values for different road adhesion coefficients.
Road Adhesion CoefficientsTireRMSE (CKF)RMSE (SCKF)Improvement Rate (%)
μ = 0.4Left front wheel0.11620.013888.1
Right front wheel0.11830.017085.6
Left rear wheel0.07900.008689.1
Right rear wheel0.08450.006292.7
μ = 0.8Left front wheel0.10640.020181.1
Right front wheel0.09990.023976.1
Left rear wheel0.07120.011583.9
Right rear wheel0.07040.009686.4
Table 3. Classification of lateral acceleration intensity levels.
Table 3. Classification of lateral acceleration intensity levels.
LevelLateral AccelerationIntensity
Normal level0 ≤ ay ≤ (0.1−0.0013u)gLow
Strong level(0.1−0.0013u)gay ≤ (0.22−0.002u)gMedium
Restricted level(0.22−0.002u)gay ≤ 0.67aymaxHigh
Maximum level0.67aymaxay ≤ 0.85aymaxVery high
Table 4. Range of maximum lateral acceleration values based on steering allocation coefficient.
Table 4. Range of maximum lateral acceleration values based on steering allocation coefficient.
Road Adhesion Coefficient μMaximum Lateral Acceleration γaymax
0.2[(0.05–0.0013u)g, 0.45g]
0.4[(0.05–0.0013u)g, 0.32g]
0.8[(0.05–0.0013u)g, 0.11g]
Table 5. Table of model simulation parameters.
Table 5. Table of model simulation parameters.
Parameter SymbolParameter MeaningNumerical ValueUnit
mVehicle mass1903kg
BfFront wheelbase1.6m
BrRear wheelbase1.6m
LaDistance from center of mass to front axle1.232m
LbDistance from center of mass to rear axle1.468m
JInertia4175kg m2
RWheel effective rolling radius325mm
CcfLateral stiffness of the front wheels66,900N/rad
CcrLateral stiffness of the rear wheels62,700N/rad
hgCenter of gravity590mm
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

Wang, H.; Wang, J.; Du, R. Research on Active Collision Avoidance Control of Vehicles Based on Estimation of Road Surface Adhesion Coefficient. World Electr. Veh. J. 2025, 16, 489. https://doi.org/10.3390/wevj16090489

AMA Style

Wang H, Wang J, Du R. Research on Active Collision Avoidance Control of Vehicles Based on Estimation of Road Surface Adhesion Coefficient. World Electric Vehicle Journal. 2025; 16(9):489. https://doi.org/10.3390/wevj16090489

Chicago/Turabian Style

Wang, Hongxiang, Jian Wang, and Ruofei Du. 2025. "Research on Active Collision Avoidance Control of Vehicles Based on Estimation of Road Surface Adhesion Coefficient" World Electric Vehicle Journal 16, no. 9: 489. https://doi.org/10.3390/wevj16090489

APA Style

Wang, H., Wang, J., & Du, R. (2025). Research on Active Collision Avoidance Control of Vehicles Based on Estimation of Road Surface Adhesion Coefficient. World Electric Vehicle Journal, 16(9), 489. https://doi.org/10.3390/wevj16090489

Article Metrics

Back to TopTop