Next Article in Journal
More Than 50-Fold Enhanced Nonlinear Optical Response of Porphyrin Molecules in Aqueous Solution Induced by Mixing Base and Organic Solvent
Next Article in Special Issue
Multi-Objective Optimisation of Tyre and Suspension Parameters during Cornering for Different Road Roughness Profiles
Previous Article in Journal
Effect of Micro-Silica Addition into Electric Arc Furnace Steel Slag Eco-Efficient Concrete
Previous Article in Special Issue
Empirical Models for the Viscoelastic Complex Modulus with an Application to Rubber Friction
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Handling Enhancement of Autonomous Emergency Steering for Reduced Road Friction Using Steering and Differential Braking

Department of Vehicle Engineering, National Taipei University of Technology, Taipei 10608, Taiwan
*
Author to whom correspondence should be addressed.
Appl. Sci. 2021, 11(11), 4891; https://doi.org/10.3390/app11114891
Submission received: 29 April 2021 / Revised: 22 May 2021 / Accepted: 24 May 2021 / Published: 26 May 2021

Abstract

:
Steering has more potential than braking to prevent rear-end collisions at higher relative velocities. A path tracking controller based on multi-input multi-output (MIMO) model predictive control (MPC) is proposed to enhance the handling performance of autonomous emergency steering in this paper. A six-state MIMO bicycle model including actuator dynamics of steering and differential braking is used for model prediction. Two control inputs are front wheel steering angle and direct yaw moment. Two model outputs are lateral displacement and heading angle. According to the work load ratios at four wheels, control allocation is used to determine the optimal braking force distribution to prevent tire force saturation. The performance of a single-input single-output (SISO) MPC that uses only steering angle control to track the lateral displacement of the desired path is employed to benchmark the performance of the proposed algorithm. Simulation results show that both SISO MPC and MIMO MPC can track the path on nominal road surface with high road friction coefficient of 0.9. For a road surface with medium road friction coefficient of 0.7, the SISO MPC is unable to track the path and loses directional stability. However, the MIMO MPC can still track the path and demonstrate robust path tracking and handling enhancement against model uncertainty due to reduced road friction.

1. Introduction

According to Traffic Safety Facts [1], rear-end collisions account for 18% of the fatal collisions between motor vehicles. Singh et al. [2] pointed out that driver error is the primary cause for most accidents. The main factor is the recognition error caused by driver inattention, internal and external distractions, and inadequate surveillance. Advanced driver assistance systems (ADAS) can assist the driver to prevent possible collisions with the obstacle in front of the vehicle via braking or steering. Bosch [3] reported that the autonomous emergency braking (AEB) system would reduce 30% of rear-end collisions. Alfred et al. [4] showed that the necessary minimum distance to avoid a collision by steering is smaller than that by braking for maneuvers with large relative velocities. Especially for a suddenly appearing obstacle, AEB is not able to avoid a collision due to insufficient braking distance. The European New Car Assessment Programme introduced safety ratings for AEB in 2014, and has announced that [5] emergency steering assist (ESA) and autonomous emergency steering system (AES) tests will start in 2020 and 2022, respectively. The goal of the tests is to deliver a further significant reduction in crashes and casualties.

1.1. Related Work

Both ESA and AES can make a sudden lane change or evasive maneuver via steering actions to avoid a collision. The main difference between ESA and AES is the trigger mechanism. When the ESA [6,7,8,9] detects the risk of collision and the steering torque from the driver, the system provides additional overlay torques to adjust the steering angle to track the evasive path without collision or directional instability. However, Shimizu et al. [10] showed that 37.9% of drivers did not take any avoidance maneuvers when encountering the approaching danger. Therefore, collision avoidance cannot be guaranteed for inattentive maneuvers with late steering actions from the driver. Unlike ESA, the AES [11,12,13,14,15] can steer automatically when the detected risk of collision is over the designed threshold.
Three types of planning approaches, search-based, optimization-based, and parameter-based, are commonly used for generating a desired path to avoid the collision. Search-based methods [16,17,18] are designed to generate an action set of multiple drivable trajectories, allowing an adjacent behavior planner to pick the most appropriate action for the global state in the scene. Optimization-based methods [19,20,21] plan the path from a mapping run and offline compute an optimal trajectory around the track using the trajectory optimization module to maximize the progress rate, and minimize slip angle cost and input rate. However, the first and second types of planning approaches are not easy to implement on production control units due to high computation loads. Parameter-based methods [7] including circular, sine/cosine, s-shape, polynomial, and trapezoidal-acceleration-profile (TAP) trajectories are designed by specifying the desired lateral displacement for a lane change maneuver that can also be employed for collision avoidance. Among the parameter-based methods, only TAP can consider transition time and ride comfort at the same time [22].
Two types of path tracking controllers, model-free and model-based, are commonly used for tracking an evasive path. If the dynamic model of the plant to be controlled is not needed for the controller design, it is classified as the model-free approach. The conventional model-free controller calculates the steering angle command based on the lateral displacement error and the heading error at the previewed point [23,24,25]. Machine learning can also be classified as the model-free approach. A neural network model can be trained to generate the steering action using the dataset of human drivers [26] or deep reinforcement learning [27]. However, the major challenge is the difficulty in proving the safety issue of these methods [28]. As for model-based approaches, the single-input single-output (SISO) model predictive control (MPC) is often used to obtain the vehicle steering angle based on a four-state bicycle model, which is used to predict the future lateral displacement of a vehicle [29,30,31].
Differential braking via electric hydraulic braking (EHB) can be used to generate the desired direct yaw moment (DYM) to improve path tracking performance. Falcone et al. [32] proposed a multi-input multi-output (MIMO) MPC controller that uses four-wheel longitudinal slip ratios and front wheel steering angle as the control input to minimize errors in heading angle, yaw rate and lateral displacement. Their simulation results showed that path error can be reduced by 50%. However, intensive computations are required for online linearization and optimization due to the complexities of the prediction model with nonlinear tire dynamics. Hajiloo et al. [33] proposed a MIMO MPC controller to determine the optimal front lateral force and the yaw moment to improve the yaw rate responsiveness for collision avoidance without decreasing the stability. Lin et al. [34] proposed a MIMO MPC controller for AES using front wheel steering angle and direct yaw-moment control (DYC) to enhance the performance of path tracking. The pseudo inverse control allocation (CA) is used to allocate the four-wheel brake forces for generating the desired DYM. Their simulation results showed that the path tracking performance of the MIMO MPC is better than that of the conventional SISO MPC. However, the actuator dynamics of steering and differential braking are not discussed in their proposed approach. The control performance might be diminished or control lost if the actuator dynamics are not fast enough to be negligible.
Electric power steering (EPS) can be used to generate the desired front wheel steering angle. However, the actuator dynamics might cause the actual steering angle to lag slightly behind the steering angle command. Chen et al. [35] proposed a MPC controller by considering EPS actuator dynamics as a first-order model to enhance the tracking performance and ride comfort. Kim et al. [36] proposed a MPC controller by considering the EPS as a second-order model. Simulation results showed that tracking performance is improved by incorporating steering actuator dynamics in the prediction model. Thornton et al. [37] proposed a MPC controller with steering input to evaluate the average and maximum yaw rates of different actuator dynamics. Their experiment results showed that the lumped first-order dynamics can meet design objectives with low computational complexity.

1.2. Main Contributions

The proposed path-tracking controller for AES is an extension of the previous work [34] in which the actuator dynamics were neglected in the vehicle model.
  • The dynamic responses of the vehicle model in the previous work might deviate from those of the actual vehicle model with actuator dynamics for severe maneuvers. The EPS and EHB dynamics are integrated with the four-state bicycle model to enhance the accuracy of the prediction model.
  • A diagonal matrix with components of tire workload ratios is used to replace the identity weighting matrix of CA to prevent saturating tire forces while generating the desired DYM.
  • Different road friction coefficients are used for sensitivity analysis to evaluate the robustness and handling enhancement of the proposed algorithm at different vehicle velocities via simulation studies.

1.3. Organization

The remainder of this paper is organized as follows: system modeling for controller design is briefly introduced in Section 2, followed by the proposed algorithm in Section 3. Simulation results are presented in Section 4. Finally, conclusions are made in Section 5.

2. Modeling

2.1. Actuator Dynamics

First-order actuator dynamics of EPS and EHB as shown below are included in the plant model for MPC.
δ ˙ f = 1 τ E P S δ f + 1 τ E P S δ f , r
M ˙ z = 1 τ E H B M z + 1 τ E H B M z , r
where δ f , r and M z , r are the control commands of the front wheel steering angle and DYM, respectively;   δ f and M z are the responses of front wheel steering angle and DYM, respectively; τ E P S and τ E H B are the time constants of EPS and EHB, respectively. τ E P S is set to be 0.125 s [37] and τ E H B is set to be 0.1 s [38] in this paper.

2.2. Bicycle Model

The six-state bicycle model is obtained by integrating the actuator dynamics with the four-state bicycle model that is linearized using small angle approximation and constant longitudinal velocity [39]. The state-space representation can be expressed as follows.
x ˙ = A m x + B m u y = C m x
where x = y v y ψ r δ f M z T is the state vector, u = δ f , r M z , r T is the input vector, and y = y ψ T is the output vector; v y and r are the lateral velocity and yaw rate of the vehicle, respectively; y and ψ are the lateral displacement and heading angle of the vehicle, respectively; A m , B m and C m are system matrix, input matrix and output matrix as shown below.
A m = 0 1 v x 0 0 0 0 C α f + C α r m v x 0 l r C α r l f C α f m v x v x C α f m 0 0 0 0 1 0 0 0 l r C α r l f C α f I z v x 0 l f 2 C α f + l r 2 C α r I z v x l f C α f I z 1 I z 0 0 0 0 1 τ E P S 0 0 0 0 0 0 1 τ E H B
B m = 0 0 0 0 1 τ E P S 0 0 0 0 0 0 1 τ E H B T
C m = 1 0 0 0 0 0 0 0 1 0 0 0
where m is the vehicle mass; v x is the vehicle longitudinal velocity; C α f and C α r are the cornering stiffness of the front and rear axles, respectively; l f and l r are the distances from the C.G. to the front and rear axles, respectively; I z is the yaw-plane rotational inertia of vehicle. The ranks of controllability matrix C and observability matrix O of the six-state bicycle model can be calculated as follows.
r a n k C = r a n k A m A m B m A m 2 B m A m 5 B m
r a n k O = r a n k C m C m A m C m A m 2 C m A m 5 T
Since both C and O are full rank of 6, the proposed model is fully controllable and observable.

2.3. Model Discretization

A D-Class Sedan in CarSim is selected as the host vehicle to obtain the parameter values of m , a , b , and I z . Nominal values of C α f and C α r are identified on a road surface with the nominal friction coefficient of 0.9 by minimizing the path errors between the trajectory responses of CarSim and the bicycle model. The vehicle parameters used in CarSim are shown in Table 1.
For the discrete controller design, the discretized plant model can be expressed as follows.
x k + 1 = Φ m x k + Γ m u k y k = H m x k
where k denotes for the kth sample. The sample time T s is selected to be 0.04 s in this paper; u k is the discretized input vector; Φ m , Γ m and H m can be expressed as follows.
Φ m = 1 T s v x T s 0 0 0 0 C α f + C α r T s m v x + 1 0 l r C α r l f C α f m v x T s v x T s C α f T s m 0 0 0 1 T s 0 0 0 l r C α r l f C α f I z v x T s 0 l f 2 C α f + l f 2 C α r T s I z v x + 1 l f C α f T s I z T s I z 0 0 0 0 T s τ E P S + 1 0 0 0 0 0 0 T s τ E H B + 1
Γ m = 0 0 0 0 T s τ E P S 0 0 0 0 0 0 T s τ E H B T
H m = 1 0 0 0 0 0 0 0 1 0 0 0

3. Controller Design

The block diagram of the proposed algorithm is shown in Figure 1. The path planning module generates the reference path R s using the trapezoidal acceleration profile [7]. The six-state bicycle model is used to predict the future path. The PGC calculation module calculates the PGC index from R s . The optimizer module is used to compute the best set of future control commands. The first two elements of the set are used as the desired control commands of front wheel steering angle and DYM. The CA module distributes brake pressure at the four wheels to generate the desired DYM. After the AES is triggered, the driver is disengaged from the vehicle until the driver’s intent to override the system is detected.

3.1. Model Predictive Controller

The predicted state vectors in the prediction horizon Np with the future control commands in the control horizon Nc can be expressed as follows.
x k , i + 1 = Φ m x k , i + Γ m u k , i x k , i + 2 = Φ m 2 x k , i + Φ m Γ m u k , i + Γ m u k , i + 1 x k , i + N p = Φ m N p x k , i + Φ m N p 1 Γ m u k , i + + Φ m N p N c Γ m u k , i + N c 1
where the initial condition of the state vector x k , i can be expressed as follows.
x k , i = 0 v ^ y 0 r δ f M ^ z T
where the initial lateral displacement and heading angle are zero in the body coordinates of the vehicle;   r and δ f can be measured using yaw rate and steering angle sensors, respectively; v ^ y is the estimated lateral velocity that can be estimated using localization-based [40] or inertial-measurement-unit-based [41] approaches; M ^ z can be estimated using estimated logitudinal tire forces as follows.
M ^ z = B C A F ^ x
where F ^ x is the estimated longitudinal tire force that can be estimated using a closed-loop disturbance estimator [42];   B C A is the effective matrix as shown below.
B C A = d 2 c o s δ f + l f s i n δ f       d 2       d 2 c o s δ f + l f s i n δ f       d 2
where d is the track width of the vehicle.
The predicted output vectors in the prediction horizon Np can be expressed as follows.
y p , k , i + 1 = H m Φ m x k , i + H m Γ m u k , i y p , k , i + 2 = H m Φ m 2 x k , i + H m Φ m Γ m u k , i + H m Γ m u k , i + 1 y p , k , i + N p = H m Φ m N p x k , i + H m Φ m N p 1 Γ m u k , i + + H m Φ m N p N c Γ m u k , i + N c 1
From Equations (11) and (15), the augmented prediction model can be formulated as follows.
Y p = F x k , i + G U p
where U p is the input vector; Y p is the output vector; F and G are the system and input matrices, respectively. They are defined as follows.
U p = u k , i T u k , i + 1 T u k , i + N c 1 T T
Y p = y p , k , i + 1 T y p , k , i + 2 T y p , k , i + N p T T
F = H m Φ m H m Φ m 2 H m Φ m N p T
G = H m Γ m 0 0 H m Φ m Γ m H m Γ m 0 H m Φ m N p 1 Γ m H m Φ m N p 2 Γ m H m Φ m N p N c Γ m
The optimizer calculates the optimal U p to minimize the cost function J p as shown below.
J p = R s Y p T Q R s Y p + U p T R ¯ U p
where R s is the reference input in the prediction horizon; Q and R ¯ are weighting matrices. They are defined as follows.
R s = r r , k , i + 1 T r r , k , i + 2 T r r , k , i + N p T T
r r , k , i + 1 = y r , k , i + 1 ψ r , k , i + 1 T  
Q = Q 1 0 0 Q 2 0 0 0 0 0 0 0 0 Q 1 0 0 Q 2 2 N p × 2 N P
R ¯ = R 1 0 0 R 2 0 0 0 0 0 0 0 0 R 1 0 0 R 2 2 N c × 2 N c    
where y r is the desired lateral displacement; ψ r is the desired heading angle; Q 1 is the weighting of lateral displacement error; Q 2 is the weighting of heading angle error; R 1 is the weighting of the steering angle; R 2 is the weighting of the DYM. These weightings are designed using Bryson’s rule [43] as shown below.
Q 1 = 1 y e , m a x 2 ;   Q 2 = 1 ψ e , m a x 2
  R 1 = 1 δ f , m a x 2 ;   R 2 = 1 M z , m a x 2
where y e , m a x is the maximum allowable lateral displacement error; ψ e , m a x is the maximum allowable heading angle error; δ f , m a x is the maximum allowable steering angle; M z , m a x is the maximum allowable DYM. The optimal U p can be obtained as follows.
U p = G T Q G + R 1 G T Q R s F x k , i
The current optimal control input u k , i is equal to the vector that consists of the first and second components of U p as follows.
u k , i = U p 1 U p 2 T

3.2. Evasive Path Generation

The desired evasive path is shown in Figure 2. A Trapezoidal Acceleration Profile (TAP) is used to design the desired global lateral displacement of the evasive path [7]. The lateral acceleration can be obtained by specifying the maximum allowable a y , m a x , the maximum allowable jerk J y , m a x , and the evasive lateral displacement y e v a . t 1 and t 2 of the TAP can be expressed as follows [7].
t 1 = a y , m a x J y , m a x ,   t 2 = t 1 2 + t 1 4 + 4 t 1 y e v a J y 2 t 1
where a y , m a x = μ ^ g ; g is the gravity; μ ^ is the estimated road friction coefficient that is assumed to be obtained from other approaches [44,45,46]. The desired global lateral position Y d of the evasive path can then be obtained as follows by integrating the global lateral acceleration Y ¨ d twice [7].
Y d ( t ) = 1 6 J y , m a x t 3 f o r   0 t t 1 Y d , 1 + v y , 1 t t 1 + 1 2 a y , m a x t t 1 2 f o r   t 1 < t t 2 Y d , 2 + v y , 2 t t 2 + 1 2 a y , m a x t t 2 2 1 6 J y , m a x t t 2 3 f o r   t 2 < t t 3 Y d , 3 + v y , 3 t t 3 1 2 a y , m a x t t 3 2 f o r   t 3 < t t 4 Y d , 4 + v y , 4 t t 4 1 6 J y , m a x t t 4 3 f o r   t 4 < t t 5 y e v a f o r   t > t 5
where v y , i = v y t i , Y d , i = Y d t i ,   i 0 , 5 . By assuming the vehicle longitudinal velocity v x is constant along the evasive path, the desired global longitudinal velocity X ˙ d of the evasive path can then be obtained as follows.
X ˙ d t = v x 2 Y ˙ d t
where v x , 0 is the initial longitudinal velocity of vehicle; Y ˙ d is the global lateral velocity that can be obtained by integrating Y ¨ d in Equation (31). We can then obtain the desired global X d by integrating X ˙ d .
The station number of the evasive path S d that is the distance along the designed evasive path can be defined as follows.
S d , j + 1 = S d , j + X d , j X d , j 1 2 + Y d , j Y d , j 1 2
where j denotes the j th sample point of the evasive path. The initial values of X d , Y d , Y ˙ d , and S d are set to be zero. The desired evasive path can then be expressed as functions of the station number as follows.
X d = f S X S d , Y d = f S Y S d
The station number in the prediction horizon can be defined as follows with a constant v x .
S p , k + i + 1 = S p , k + i + v x i T s , i 0 ,   1 , ,   N p 1
where the initial station number S p , k is the current station number S c . The desired evasive path in the preview horizon can then be expressed as follows.
X p , k = f S X S p , k , Y p , k = f S Y S p , k
The desired evasive path in the body coordinates of the vehicle can be calculated using coordinate transformation as shown below.
x r , k y r , k = c o s Ψ c s i n Ψ c s i n Ψ c c o s Ψ c X p , k X c Y p , k Y c
where Ψ c is the current global heading angle of vehicle; X c and Y c are the current global position of the vehicle, respectively; x r and y r are the local coordinates of the evasive path. X c , Y c , Ψ c and S c are assumed to be available from the localization system. The desired lateral displacement of the evasive path can be expressed as y r = f r x r in the body coordinates of the vehicle. The heading angle reference, which is the first derivative of the desired path, can then be approximated as follows.
ψ r , k + i = f r x r , k + i = f r x r , k + i + 1 f r x r , k + i x r , k + i + 1 x r , k + i

3.3. Control Allocation

Weighted pseudo inverse with constraints [47] is used to obtain the distributed brake forces at four wheels. The DYM command M z , r can be expressed as follows.
M z , r = B C A F x
where F x is the tire force vector that consists of four tire forces.
F x = F x , f l F x , r l F x , f r F x , r r T
where the subscripts fl, rl, fr, and rr denote quantities at front-left, rear-left, front-right, and rear-right tires, respectively.
The pseudo inverse solution is a two-norm solution to the CA problem that can be formulated as follows.
m i n F x J C A = m i n F x 1 2 F x + C C A T W C A F x + C C A  
subject to:
M z , r = B C A F x
F x , m i n F x 0
where C C A is the offset vector used to represent off-nominal condition with one or more tire forces; F x , m i n is the vector used to represent the minimum allowable tire forces. The maximum allowable tire forces are set to be 0 such that only braking forces are used. The optimal distribution can then be obtained as follows.
F x = C C A + B C A # M z , r + B C A C C A
B C A # = W C A 1 B C A T B C A W C A 1 B C A T 1
where B C A # is the pseudo inverse of B C A . The C C A is zero in the normal condition, so (44) can be simplified as follows.
F x = B C A # M z , r
where the diagonal weighting matrix W C A is designed with elements equal to the estimated tire workload ratios as follows [42] to prevent saturating tire forces. The larger the ratio is, the closer to saturation the corresponding tire force is. Thus, tire forces that are needed for generating the desired DYM are distributed to tires with lower tire work load ratios.
W C A = ρ ^ f l 0 0 0 0 ρ ^ r l 0 0 0 0 ρ ^ f r 0 0 0 0 ρ ^ r r    
where ρ ^ is the estimated tire workload ratio of each tire that can be obtained as follows [42].
ρ ^ = F ^ x 2 + F ^ y 2 F ^ z 2
where F ^ x , F ^ y and F ^ z are the estimated tire forces at longitudinal, lateral and normal directions, respectively. If the ith element of F x exceeds the boundary values, the corresponding ith element in C C A is set to be the opposite number of the boundary value and the corresponding ith element in B C A is set to be zero. The adjusted vectors B C A , a and C C A , a can be obtained using the Algorithm 1 as shown below.
Algorithm 1 Saturation Prevention
B C A , a = B C A ; C C A , a = C C A ;
if   F x i > 0
                      B C A , a i = 0
else if   F x i < F x , m i n i
                      B C A , a i = 0
                      C C A , a i = F x , m i n i
end
After obtaining the adjusted vectors, we can replace B C A and C C A with B C A , a and C C A , a , respectively, and obtain the adjusted tire force vector using Equations (44) and (45).
The four-wheel brake pressure command P b , r can be expressed as follows.
P b , r = F x d i a g r w G b , f r w G b , r r w G b , f r w G b , r  
where G b , f and G b , r are the brake gains of front and rear wheels, respectively; r w is the wheel radius; diag is a function that creates a square diagonal matrix with the input elements on the main diagonal. The EHB module is used to generate four-wheel brake pressure P b .

4. Simulation Results

The proposed algorithm was evaluated using CarSim in MATLAB/Simulink. Figure 3 shows the test scenario used in this paper. There was one moving vehicle and one stationary vehicle in front of the host vehicle. After the front moving vehicle changed lanes at the last moment [48], the stationary vehicle was detected as a suddenly appearing obstacle by the CarSim Sensor module of the host vehicle at 5 m ahead the last point to steer (LPS) [4], which was defined as the last location to avoid a collision by steering. The longitudinal vehicle velocity was set at 80 km/h which is the highest longitudinal velocity for testing ESA. Since the stationary vehicle suddenly appeared in front of the host vehicle, the last point to brake (LPB), which was defined as the last location to avoid the collision by braking, was already behind the host vehicle. A single lane-change path generated using TAP was used as the evasive path to avoid the collision. When the host vehicle arrived at the LPS, the AES was trigged automatically.
The maximum angular rate of the front wheel steering angle was limited to 42 ° / s due to the EPS according to the requirement of the fishhook test [49]. The front wheel steering angle was limited between 35 ° and 35 ° due to the pinion-rack configuration. Simulation results of the proposed MIMO MPC were compared with those of the SISO MPC [35]. For the first test scenario, the nominal road friction coefficient was 0.9 which was used to obtain the nominal cornering stiffness of the prediction model in MPC. The second test scenario was used to test the robustness of the proposed algorithm with a medium road friction coefficient of 0.7 which is 22% less than the nominal value; i.e., the actual cornering stiffness should be smaller than the nominal values used in the prediction model.

4.1. Comparison of Prediction Models

An open-loop test was used to compare the responses of three bicycle models. The structures of these models are listed in Table 2. The four-state bicycle model [34] has two inputs and two outputs that are the same as those of the proposed six-state bicycle model in (3). However, the actuator dynamics of EPS and EHB were not considered for the four-state bicycle. The five-state bicycle model that includes the EPS actuator dynamics has one steering angle control input and the lateral displacement output. The DYM input was not considered in the five-state bicycle model. Dynamic responses of these models are shown in Figure 4. The step steering angle input was applied at the beginning of simulation, and the DYM step input was applied at 1 s. CarSim denotes the dynamic responses of CarSim with two inputs of steering angle and DYM. Before 1 s, the main difference between the four-state model and other models was the transient response due the lack of actuator dynamics. The steady-state responses of three bicycle models were almost the same. The responses of the five-state and the six-state bicycle models were similar to those of CarSim. After the DYM was applied at 1 s, only the responses of the six-state bicycle model were close to those of CarSim. Since the six-state model with actuator dynamics can achieve both transient and steady-state responses closest to those of CarSim, it was used as the prediction model in the proposed algorithm.

4.2. Nominal Road Friction Coefficient of 0.9

The simulation results with accurately estimated road-friction coefficient of 0.9, which is used to obtain the maximum allowable lateral acceleration for designing the desired evasive path, are shown in Figure 5, Figure 6 and Figure 7. The AES is assumed to be triggered at 3 s. SISO MPC and MIMO MPC can track the desired evasive path and complete the lane change maneuver.
Path tracking responses are shown in Figure 5. SISO MPC and MIMO MPC have similar responses of global lateral displacement. However, their global heading angle responses are less similar to each other. As can be seen from the vehicle dynamic responses in Figure 6, the values of y e of MIMO MPC are more negative than those of SISO MPC between 3.1 and 3.7 s. Thus, the lane change response of MIMO MPC is faster than that of SISO MPC at the beginning of lane change due to the additional DYM input. Meanwhile, the heading angle errors of MIMO MPC are smaller than those of SISO MPC during the lane change maneuver.
Figure 7 shows control commands and actuator responses. At the beginning of AES, MIMO MPC and SISO MPC have the same steering angle responses due to the angular rate limitation and the actuator dynamics of EPS. However, MIMO MPC has an additional DYM input, which can accelerate the response of r and reduce the maximum steering angle to be smaller than that of SISO MPC. Since the heading angle is the integration of yaw rate, faster response of r can lead to smaller ψ e . The comparison of the β r phase plane plots is shown in Figure 8. MIMO MPC has better convergences due to a smaller circling area around the origin. This means that MIMO MPC can reduce β in order to enhance handling performance and directional stability. Although DYM is generated using braking forces, the vehicle longitudinal velocity of MIMO MPC is only reduced slightly compared to that of SISO MPC.

4.3. Nominal Road Friction Coefficient of 0.7

The simulation results with a medium road friction coefficient of 0.7, which is 22% less than the nominal value, are shown in Figure 9, Figure 10, Figure 11, Figure 12 and Figure 13. Assuming the AES is not aware of the overestimation of the road friction coefficient, the nominal value of 0.9 is still used to design the evasive path and the nominal cornering stiffnesses are still used in the prediction model.
Path tracking responses are shown in Figure 9. The AES is assumed to be triggered at 3 s. SISO MPC cannot complete the lane change maneuver and loses the directional stability. Conversely, MIMO MPC can track the desired evasive path and complete the lane change maneuver successfully. Similar to the analysis of Figure 8 in Section 4.1, we found that MIMO MPC has a lane change response faster than that of SISO MPC at the beginning of lane change, as shown in Figure 10. Meanwhile, the peak heading angle error of MIMO MPC is smaller than that of SISO MPC at about 4 s due to minimizing y e and ψ e simutaneously via both steering and DYM. From the yaw rate response, we can observe that the vehicle with SISO MPC starts to spin continuously after 4 s.
As can be seen from Figure 11, SISO MPC requires steering angles much larger than those of MIMO MPC after 4 s. Although SISO MPC tries to correct the steering angle as fast as possible, the steering angle response is not fast enough due to the angular rate limitation and actuator dynamics. Figure 12 shows that the side-slip angle of SISO MPC increases rapidly with large yaw rate after passing β = 0 . It also confirms the directional instability of SISO MPC. On the other hand, the β r phase plane plot of MIMO MPC converges to the origin after completing the lane change maneuver.
Figure 13 and Figure 14 show the responses of tire slip angle and lateral tire forces at four wheels. The dashed lines indicate the thresholds of the tire slip angles to saturate lateral tire forces. The front lateral tire forces of SISO MPC are found to be saturated at 4.1 s. Even though the steering angle of SISO MPC in Figure 11 is still increasing after 4 s, the corresponding lateral tire forces are not increased due to saturation as shown in Figure 14. Since the lateral tire force is no longer increased with the increment of the tire slip angle, the prediction model used in MPC is not accurate anymore. Thus, SISO MPC cannot effectively control the vehicle to track the desired evasive path and prevent directional instability. Although the rear tire slip angles of MIMO MPC are saturated around 4.5 s, the front tire slip angles are not saturated. Thus, the front tires can still provide more lateral tire forces via increasing the steering angle input if necessary. Meanwhile, MIMO MPC has additional DYM which can improve the responses of r and prevent saturating the reference command of the steering angle. Figure 15 shows the responses of tire workload ratios. The CA distributes the longitudinal tire forces as shown in Figure 16 to the wheels with lower tire workload ratios in order to generate the required DYM without saturating the tire forces; thus, demonstrating better, more robust control performance and handling enhancement against model uncertainty due to reduced road friction coefficient.

4.4. Sensitivity Analysis

The estimated road friction coefficient be used not only for evasive path generation, but also for obtaining the equivalent front and rear cornering stiffnesses of the bicycle model used in MPC via a look-up table. However, the estimation might not be accurate due to the lack of enough excitation. Different road friction coefficients deviated from the estimated nominal value of 0.9 are used for sensitivity analysis to evaluate the robustness of the proposed algorithm. The minimum distance D L [50] between the host vehicle and the stationary vehicle to be avoided as shown in Figure 17 can be defined as follows.
D L = x 1 x 2 2 + y 1 y 2 2 W h 2 W s 2
where P h x 1 , y 1 is the front center point of host vehicle; P s x 2 , y 2 is the front center point of stationary vehicle; W h is the width of host vehicle; W s is the width of stationary vehicle. D L at different road friction coefficients are shown in Table 3. The collision can be avoided for all simulated scenarios.
The vehicle sideslip angle can be used to evaluate the yaw stability of the vehicle. The root-mean-square (rms) and maximum (max) values of sideslip angle responses at different road friction coefficients are shown in Table 4. Those values are obtained using the responses from the beginning of control at 3–10 s. The more the road friction coefficient deviates from the nominal value of 0.9, the larger the rms and max values of sideslip angles are. MIMO can stabilize the vehicle in the new target lane for all scenarios. However, SISO exhibits large lateral responses as shown in Figure 10 and cannot stabilize the vehicle in the new target lane for μ 0.75 . The rms and max values of sideslip angle suddenly increase for μ 0.75 which are indications of yaw instabilities. Thus, MIMO demonstrates better robustness of yaw stability and handling performance for reduced road friction coefficients.
In order to evaluate the robustness of the proposed algorithm at different velocities, the longitudinal velocity of host vehicle is increased to 120 km/h in Figure 18. The suddenly appearing obstacle is assumed to be detected at 7.5 m ahead of the LPS.   D L at different road friction coefficients is shown in Table 5. Similar to the results in Table 3, the collision can be avoided for all simulated scenarios. The rms and max values of sideslip angle responses at different road friction coefficients are shown in Table 6. Similar to the results in Table 4, the more the road friction coefficient deviates from the nominal value of 0.9, the larger the rms and max values of sideslip angles are. MIMO can stabilize the vehicle in the new target lane for all scenarios. However, the rms and max values of sideslip angle suddenly increase for μ 0.65 which are indications of yaw instabilities. Thus, MIMO demonstrates better robustness of yaw stability and handling performance for reduced road friction coefficients even at a much higher longitudinal vehicle velocity of 120 km/h.

5. Conclusions

MIMO MPC was employed to design the path tracking controller for autonomous emergency steering using steering and differential braking. The prediction model was based on a six-state road following bicycle model including the actuator dynamics of EPS and EHB. For nominal road friction, the path tracking responses of SISO MPC (using steering only) and MIMO MPC (using both steering and differential braking) are very similar, but the directivity of MIMO MPC can be improved by DYM. The usage of steering angle can be reduced, and the handling performance of MIMO MPC is better than SISO MPC. For medium road friction, SISO MPC is unable to track the path and loses directional stability. However, MIMO MPC can still reduce the maximum required steering angle and accelerate the response of r via DYM. In order to prevent tire force saturation, the CA can distribute the longitudinal tire forces to wheels with lower tire work load ratios for generating the desired DYM. Thus, MIMO MPC can achieve robust path tracking and handling enhancement against model uncertainty due to road friction reduced by 22% and 33% at 80 and 120 km/h, respectively. In this paper, the handling performance was mainly discussed for avoiding the collision with a stationary vehicle via lateral dynamics control. For a slow moving vehicle in front of the host vehicle, collision avoidance via AES should be further investigated to demonstrate the effectiveness the proposed algorithm. Since the lateral tire forces at front steering wheels are affected by load transfer that can be created via acceleration or braking, coordinated longitudinal and lateral dynamics control might further enhance the handling performance for collision avoidance.

Author Contributions

Conceptualization, B.-C.C. and Y.-M.L.; methodology, B.-C.C. and Y.-M.L.; software, Y.-M.L.; validation, Y.-M.L.; formal analysis, B.-C.C. and Y.-M.L.; writing—original draft preparation, Y.-M.L.; writing—review and editing, B.-C.C.; project administration, B.-C.C. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by Ministry of Science and Technology (MOST, Taipei, Taiwan), grant number MOST-109-2218-E-027-004.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Acknowledgments

The authors would like to thank the Ministry of Science and Technology (MOST, Taipei, Taiwan) for supporting this research.

Conflicts of Interest

The authors declare no conflict of interest. The funding sponsors had no role in the design of the study; in the collection, analysis, or interpretation of data; in the writing of the manuscript, and in the decision to publish the results.

References

  1. NHTSA. Traffic Safety Facts 2017 a Compilation of Motor Vehicle Crash Data; NHTSA: Washington, DC, USA, 2019.
  2. Singh, S. Critical Reasons for Crashes Investigated in the National Motor Vehicle Crash Causation Survey. Available online: https://crashstats.nhtsa.dot.gov/Api/Public/ViewPublication/812506 (accessed on 24 May 2021).
  3. Lich, T.; Mettler, A.; Georgi, A.; Danz, C.; Doopyo, L.; Sooncheol, L.; Sul, J. Benefit Analysis of Predictive Rear End Collision Avoidance and Mitigation Systems for South Korea Using Video Documented Accident Data. In Proceedings of the 11th International Symposium on Advanced Vehicle Control, Seoul, Korea, 9–12 September 2012. [Google Scholar]
  4. Eckert, A.; Hartmann, B.; Sevenich, M.; Rieth, P. Emergency Steer & Brake Assist—A Systematic Approach for System Integration of Two Complementary Driver Assistance Systems. In Proceedings of the 22nd ESV Enhanced Safety of Vehicles Conference, Washington, WA, USA, 13–16 June 2011. [Google Scholar]
  5. EuroNCAP. Euro NCAP 2025 Roadmap; EuroNCAP: Leuven, Belgium, 2018. [Google Scholar]
  6. Choi, J.; Yi, K. Design and Evaluation of Emergency Driving Support Using Motor Driven Power Steering and Differential Braking on a Virtual Test Track. SAE Int. J. Passeng. Cars–Mech. Syst. 2013, 6, 691–704. [Google Scholar] [CrossRef]
  7. Choi, J.; Yi, K.; Suh, J.; Ko, B. Coordinated Control of Motor-Driven Power Steering Torque Overlay and Differential Braking for Emergency Driving Support. IEEE Trans. Veh. Technol. 2014, 63, 566–579. [Google Scholar] [CrossRef]
  8. Keller, M.; Hass, C.; Seewald, A.; Bertram, T.; Keller, M. Driving simulator study on an emergency steering assist. In Proceedings of the 2014 IEEE International Conference on Systems, Man, and Cybernetics (SMC), San Diego, CA, USA, 5–8 October 2014; pp. 3008–3013. [Google Scholar]
  9. Zhao, Z.; Zhou, L.; Luo, Y.; Li, K. Emergency Steering Evasion Assistance Control Based on Driving Behavior Analysis. IEEE Trans. Intell. Transp. Syst. 2018, 20, 457–475. [Google Scholar] [CrossRef]
  10. Shimizu, M.; Usami, M.; Fujinami, H. Development of Collision-Avoidance Assist System Operating at Driver Steering. Trans. Soc. Automot. Eng. Jpn. 2008, 39, 441–446. [Google Scholar] [CrossRef]
  11. Choi, C.; Kang, Y. Simultaneous braking and steering control method based on nonlinear model predictive control for emergency driving support. Int. J. Control. Autom. Syst. 2017, 15, 345–353. [Google Scholar] [CrossRef]
  12. Ferdinand, J.; Yi, B. Trajectory planning for collision avoidance in urban area. In Proceedings of the 2016 IEEE Intelligent Vehicles Symposium (IV), Gothenburg, Sweden, 19–22 June 2016; pp. 202–207. [Google Scholar]
  13. Hayashi, R.; Isogai, J.; Raksincharoensak, P.; Nagai, M. Autonomous collision avoidance system by combined control of steering and braking using geometrically optimised vehicular trajectory. Veh. Syst. Dyn. 2012, 50, 151–168. [Google Scholar] [CrossRef] [Green Version]
  14. Zhou, L.; Zhao, Z.; Shen, P.; Li, M.; Li, K. Emergency Steering Evasion Control by Combining the Yaw Moment with Steering Assistance. In Proceedings of the SAE 2018 World Congress and Exhibition, Detroit, MI, USA, 10–12 April 2018. [Google Scholar] [CrossRef]
  15. Cui, Q.; Ding, R.; Wu, X.; Zhou, B. A new strategy for rear-end collision avoidance via autonomous steering and differential braking in highway driving. Veh. Syst. Dyn. 2019, 58, 955–986. [Google Scholar] [CrossRef]
  16. Zhang, Y.; Chen, H.; Waslander, S.L.; Gong, J.; Xiong, G.; Yang, T.; Liu, K. Hybrid Trajectory Planning for Autonomous Driving in Highly Constrained Environments. IEEE Access 2018, 6, 32800–32819. [Google Scholar] [CrossRef]
  17. Stahl, T.; Wischnewski, A.; Betz, J.; Lienkamp, M. Multilayer Graph-Based Trajectory Planning for Race Vehicles in Dynamic Scenarios. In Proceedings of the 2019 IEEE Intelligent Transportation Systems Conference (ITSC), Paris, France, 9–12 June 2019. [Google Scholar]
  18. McNaughton, M.; Urmson, C.; Dolan, J.M.; Lee, J.-W. Motion planning for autonomous driving with a conformal spatiotemporal lattice. In Proceedings of the 2011 IEEE International Conference on Robotics and Automation, Shanghai, China, 9–13 May 2011; pp. 4889–4895. [Google Scholar]
  19. Srinivasan, S.; Giles, S.N.; Liniger, A. A Holistic Motion Planning and Control Solution to Challenge a Professional Racecar Driver. arXiv 2021, arXiv:2103.00358. Available online: https://arxiv.org/abs/2103.00358 (accessed on 24 May 2021).
  20. Qian, X.; Altché, F.; Bender, P.; Stiller, C.; Fortelle, A. La Optimal Trajectory Planning for Autonomous Driving Integrating Logical Constraints: An MIQP Perspective. In Proceedings of the 2016 IEEE 19th International Conference on Intelligent Transportation Systems, Rio de Janeiro, Brazil, 1–4 November 2016; pp. 205–210. [Google Scholar]
  21. Dolgov, D.; Thrun, S.; Montemerlo, M.; Diebel, J. Path Planning for Autonomous Vehicles in Unknown Semi-structured Environments. Int. J. Robot. Res. 2010, 29, 485–501. [Google Scholar] [CrossRef]
  22. Nelson, W. Continuous-curvature paths for autonomous vehicles. In Proceedings of the 1989 International Conference on Robotics and Automation, Scottsdale, AZ, USA, 14–19 May 1989; Volume 3, pp. 1260–1264. [Google Scholar]
  23. Sotelo, M.A. Lateral control strategy for autonomous steering of Ackerman-like vehicles. Robot. Auton. Syst. 2003, 45, 223–233. [Google Scholar] [CrossRef]
  24. Cremean, L.B.; Foote, T.B.; Gillula, J.H.; Hines, G.H.; Kogan, D.; Kriechbaum, K.L.; Lamb, J.C.; Leibs, J.; Lindzey, L.; Rasmussen, C.E.; et al. Alice: An information-rich autonomous vehicle for high-speed desert navigation. J. Field Robot. 2006, 23, 777–810. [Google Scholar] [CrossRef]
  25. Chatzikomis, C.I.; Spentzas, K.N. A path-following driver model with longitudinal and lateral control of vehicle’s motion. Forsch. Ing. 2009, 73, 257–266. [Google Scholar] [CrossRef]
  26. Chen, B.; Li, L.; Zhang, W.; Dong, H.; Wang, Y.; Xiao, L. A Data-Based Approach to Path Following Controller Design for Autonomous Vehicles. In Proceedings of the CICTP 2019, Nanjing, China, 6–8 July 2019; pp. 367–378. [Google Scholar]
  27. Chen, I.-M.; Chan, C.-Y. Deep reinforcement learning based path tracking controller for autonomous vehicle. Proc. Inst. Mech. Eng. Part D J. Automob. Eng. 2020, 1–11. [Google Scholar] [CrossRef]
  28. Grigorescu, S.; Trasnea, B.; Cocias, T.; Macesanu, G. A survey of deep learning techniques for autonomous driving. J. Field Robot. 2020, 37, 362–386. [Google Scholar] [CrossRef]
  29. Chen, B.-C.; Luan, B.-C.; Lee, K. Design of lane keeping system using adaptive model predictive control. In Proceedings of the 2014 IEEE International Conference on Automation Science and Engineering (CASE), Taipei, Taiwan, 18–22 August 2014; pp. 922–926. [Google Scholar]
  30. Skarpetis, M.G.; Koumboulis, F.N.; Papanikolaou, P. Vehicle lateral control using a robust tracking controller based on vision look ahead system. In Proceedings of the 2015 International Conference on Electrical, Electronics, Signals, Communication and Optimization (EESCO), Visakhapatnam, India, 24–25 January 2017; pp. 000213–000218. [Google Scholar]
  31. Song, L.; Guo, H.; Wang, F.; Liu, J.; Chen, H. Model predictive control oriented shared steering control for intelligent vehicles. In Proceedings of the 2017 29th Chinese Control and Decision Conference (CCDC), Chongqing, China, 28–30 May 2017; pp. 7568–7573. [Google Scholar]
  32. Falcone, P.; Borrelli, F.; Asgari, J.; Tseng, H.E.; Hrovat, D. A model predictive control approach for combined braking and steering in autonomous vehicles. In Proceedings of the 2007 Mediterranean Conference on Control & Automation, Athens, Greece, 27–29 June 2007; pp. 1–6. [Google Scholar]
  33. Hajiloo, R.; Abroshan, M.; Khajepour, A.; Kasaiezadeh, A.; Chen, S.-K. Integrated Steering and Differential Braking for Emergency Collision Avoidance in Autonomous Vehicles. IEEE Trans. Intell. Transp. Syst. 2021, 22, 3167–3178. [Google Scholar] [CrossRef]
  34. Lin, Y.; Chen, B.; Chan, Y. Design of Autonomous Emergency Steering Using Multi-Input Multi-Output Model Predictive Control. In Proceedings of the Advanced Vehicle Control Proceedings of the 14th International Symposium on Advanced Vehicle Control (AVEC’18), Beijing, China, 14–18 July 2018. [Google Scholar]
  35. Chen, B.-C.; Tsai, C.-T.; Lin, Y.-M.; Lee, K. Design of an automated steering controller with steering actuator dynamics and adaptive preview time. In Proceedings of the Advanced Vehicle Control AVEC’16, Munich, Germany, 13–16 September 2016; pp. 163–168. [Google Scholar]
  36. Kim, E.; Kim, J.; Sunwoo, M. Model predictive control strategy for smooth path tracking of autonomous vehicles with steering actuator dynamics. Int. J. Automot. Technol. 2014, 15, 1155–1164. [Google Scholar] [CrossRef]
  37. Thornton, S.; Zhang, V.; Varnhagen, S.; Gerdes, J. Comparative Analysis of Steering System Models in Model Predictive Control of Automated Vehicles. In Proceedings of the 14th International Symposium on Advanced Vehicle Control (AVEC 2018), Beijing, China, 16–20 July 2018. [Google Scholar]
  38. Soltani, A.; Assadian, F.; Soltani, A. New Slip Control System Considering Actuator Dynamics. SAE Int. J. Passeng. Cars–Mech. Syst. 2015, 8, 512–520. [Google Scholar] [CrossRef] [Green Version]
  39. Ulsoy, A.G.; Peng, H.; Cakmakci, M. Automotive Control Systems; Cambridge University Press: Cambridge, UK, 2012. [Google Scholar]
  40. Wischnewski, A.; Stahl, T.; Betz, J.; Lohmann, B. Vehicle Dynamics State Estimation and Localization for High Performance Race Cars. IFAC-PapersOnLine 2019, 52, 154–161. [Google Scholar] [CrossRef]
  41. Chen, B.-C.; Hsieh, F.-C. Sideslip angle estimation using extended Kalman filter. Veh. Syst. Dyn. 2008, 46, 353–364. [Google Scholar] [CrossRef]
  42. Chen, B.-C.; Kuo, C.-C. Electronic stability control for electric vehicle with four in-wheel motors. Int. J. Automot. Technol. 2014, 15, 573–580. [Google Scholar] [CrossRef]
  43. Bryson, A.E. Control of Spacecraft and Aircraft; De Gruyter: Berlin, Germany, 1994. [Google Scholar]
  44. Ahn, C.S. Robust Estimation of Road Friction Coefficient for Vehicle Active Safety Systems; University of Michigan: Ann Arbor, MI, USA, 2011. [Google Scholar]
  45. Wielitzka, M.; Dagen, M.; Ortmaier, T. State and maximum friction coefficient estimation in vehicle dynamics using UKF. In Proceedings of the 2017 American Control Conference (ACC), Seattle, WA, USA, 24–26 May 2017; pp. 4322–4327. [Google Scholar] [CrossRef]
  46. Hermansdorfer, L.; Betz, J.; Lienkamp, M. A Concept for Estimation and Prediction of the Tire-Road Friction Potential for an Autonomous Racecar. In Proceedings of the 2019 IEEE Intelligent Transportation Systems Conference (ITSC), Auckland, New Zealand, 27–30 October 2019; pp. 1490–1495. [Google Scholar]
  47. Oppenheimer, M.W.; Doman, D.B.; Bolender, M.A. Control Allocation for Over-actuated Systems. In Proceedings of the 2006 14th Mediterranean Conference on Control and Automation, Ancona, Italy, 28–30 June 2006; pp. 1–6. [Google Scholar]
  48. Car Insurers Warn on “Autonomous” Vehicles—BBC News. Available online: https://www.bbc.com/news/technology-44439523 (accessed on 21 May 2021).
  49. NHTSA. Laboratory Test Procedure for Dynamic Rollover the Fishhook Maneuver Test Procedure; NHTSA: Washington, DC, USA, 2013.
  50. He, X.; Liu, Y.; Lv, C.; Ji, X.; Liu, Y. Emergency steering control of autonomous vehicle for collision avoidance and stabilisation. Veh. Syst. Dyn. 2018, 57, 1163–1187. [Google Scholar] [CrossRef]
Figure 1. Block diagram of the proposed algorithm.
Figure 1. Block diagram of the proposed algorithm.
Applsci 11 04891 g001
Figure 2. Evasive path planning.
Figure 2. Evasive path planning.
Applsci 11 04891 g002
Figure 3. Test scenario at 80 km/h.
Figure 3. Test scenario at 80 km/h.
Applsci 11 04891 g003
Figure 4. Open-loop test of three bicycle models.
Figure 4. Open-loop test of three bicycle models.
Applsci 11 04891 g004
Figure 5. Path tracking responses for μ = 0.9 .
Figure 5. Path tracking responses for μ = 0.9 .
Applsci 11 04891 g005
Figure 6. Path tracking responses for μ = 0.9 .
Figure 6. Path tracking responses for μ = 0.9 .
Applsci 11 04891 g006
Figure 7. Actuator responses for μ = 0.9 .
Figure 7. Actuator responses for μ = 0.9 .
Applsci 11 04891 g007
Figure 8. β r phase plane plots for μ = 0.9 .
Figure 8. β r phase plane plots for μ = 0.9 .
Applsci 11 04891 g008
Figure 9. Path tracking responses for μ = 0.7 .
Figure 9. Path tracking responses for μ = 0.7 .
Applsci 11 04891 g009
Figure 10. Responses of vehicle dynamics for μ = 0.7 .
Figure 10. Responses of vehicle dynamics for μ = 0.7 .
Applsci 11 04891 g010
Figure 11. Actuator responses for μ = 0.7 .
Figure 11. Actuator responses for μ = 0.7 .
Applsci 11 04891 g011
Figure 12. β r phase plane comparisons for μ = 0.7 .
Figure 12. β r phase plane comparisons for μ = 0.7 .
Applsci 11 04891 g012
Figure 13. Responses of tire slip angles for μ = 0.7 .
Figure 13. Responses of tire slip angles for μ = 0.7 .
Applsci 11 04891 g013
Figure 14. Responses of lateral tire forces for μ = 0.7 .
Figure 14. Responses of lateral tire forces for μ = 0.7 .
Applsci 11 04891 g014
Figure 15. Responses of tire workload ratios for μ = 0.7 .
Figure 15. Responses of tire workload ratios for μ = 0.7 .
Applsci 11 04891 g015
Figure 16. Responses of longitudinal tire forces for μ = 0.7 .
Figure 16. Responses of longitudinal tire forces for μ = 0.7 .
Applsci 11 04891 g016
Figure 17. The minimal distance between host vehicle and stationary vehicle.
Figure 17. The minimal distance between host vehicle and stationary vehicle.
Applsci 11 04891 g017
Figure 18. Test scenario at 120 km/h.
Figure 18. Test scenario at 120 km/h.
Applsci 11 04891 g018
Table 1. Vehicle parameters.
Table 1. Vehicle parameters.
NameValue
Vehicle mass (m)1530 kg
Yaw-plane rotational inertia of vehicle (Iz)2315 kg–m2
Distances from the C.G. to the front axles (lf) 1.1 m
Wheel base (L) 2.78 m
Cornering stiffness of the front axles (Cαf) 150.3 kN/rad
Cornering stiffness of the rear axles (Cαr) 104.9 kN/rad
Table 2. Structures of three bicycle models.
Table 2. Structures of three bicycle models.
ModelStateInputOutput
Four-states y ,   v y , ψ ,   r δ f ,   M z y ,   ψ
Five-states y ,   v y , ψ ,   r ,   δ f δ f , r y
Six-states y ,   v y , ψ ,   r ,   δ f ,   M z δ f , r ,   M z , r y ,   ψ
Table 3. The minimal distance between host vehicle and stationary vehicle at 80 km/h.
Table 3. The minimal distance between host vehicle and stationary vehicle at 80 km/h.
Road   Friction   Coefficient ,   μ
0.9 0.85   0.8   0.75   0.7  
SISO0.51 m0.53 m0.52 m0.47 m0.36 m
MIMO0.48 m0.49 m0.51 m0.51 m0.45 m
Table 4. Sideslip angle at different road friction coefficients at 80 km/h.
Table 4. Sideslip angle at different road friction coefficients at 80 km/h.
Road   Friction   Coefficient ,   μ
0.9 0.85   0.8   0.75   0.7  
SISOrms1.1°1.5°3.2°62.3°77.2°
max4.4°14.2°180°180°
MIMOrms1.2°1.6°2.2°3.1°
max4.3°4.7°5.9°13°
Table 5. The minimal distance between host vehicle and stationary vehicle at 120 km/h.
Table 5. The minimal distance between host vehicle and stationary vehicle at 120 km/h.
Road   Friction   Coefficient ,   μ
0.90.85 0.8 0.75 0.7 0.65 0.6  
SISO0.44 m0.45 m0.47 m0.47 m0.45 m0.39 m0.27 m
MIMO0.40 m0.42 m0.43 m0.43 m0.42 m0.36 m0.24 m
Table 6. Sideslip angle at different road friction coefficients at 120 km/h.
Table 6. Sideslip angle at different road friction coefficients at 120 km/h.
Road   Friction   Coefficient ,   μ
0.90.85 0.8 0.75 0.7 0.65 0.6
SISOrms1.7°2.2°3.1°4.3°6.2°66.7°73.2°
max5.1°6.9°9.9°13.8°19.1°180°180°
MIMOrms1.5°1.7°2.2°3.1°4.2°5.6°6.7°
max4.7°5.4°6.8°9.8°13.4°17°19.8°
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Lin, Y.-M.; Chen, B.-C. Handling Enhancement of Autonomous Emergency Steering for Reduced Road Friction Using Steering and Differential Braking. Appl. Sci. 2021, 11, 4891. https://doi.org/10.3390/app11114891

AMA Style

Lin Y-M, Chen B-C. Handling Enhancement of Autonomous Emergency Steering for Reduced Road Friction Using Steering and Differential Braking. Applied Sciences. 2021; 11(11):4891. https://doi.org/10.3390/app11114891

Chicago/Turabian Style

Lin, Yu-Min, and Bo-Chiuan Chen. 2021. "Handling Enhancement of Autonomous Emergency Steering for Reduced Road Friction Using Steering and Differential Braking" Applied Sciences 11, no. 11: 4891. https://doi.org/10.3390/app11114891

APA Style

Lin, Y.-M., & Chen, B.-C. (2021). Handling Enhancement of Autonomous Emergency Steering for Reduced Road Friction Using Steering and Differential Braking. Applied Sciences, 11(11), 4891. https://doi.org/10.3390/app11114891

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop