Next Article in Journal
Bistable Boron-Related Defect Associated with the Acceptor Removal Process in Irradiated p-Type Silicon—Electronic Properties of Configurational Transformations
Previous Article in Journal
Machine Learning Electrocardiogram for Mobile Cardiac Pattern Extraction
Previous Article in Special Issue
Outlier Vehicle Trajectory Detection Using Deep Autoencoders in Santiago, Chile
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Adaptive Cruise System Based on Fuzzy MPC and Machine Learning State Observer

1
College of Automotive Engineering, Jilin University, Changchun 130025, China
2
Intelligent and Connected Vehicle Development Institute, China FAW Corporation Limited, Changchun 130013, China
3
Key Laboratory of Bionic Engineering, Ministry of Education, Jilin University, Changchun 130025, China
*
Author to whom correspondence should be addressed.
Sensors 2023, 23(12), 5722; https://doi.org/10.3390/s23125722
Submission received: 24 April 2023 / Revised: 9 June 2023 / Accepted: 17 June 2023 / Published: 19 June 2023
(This article belongs to the Special Issue Sensing, Optimization, and Navigation on Vehicle Control)

Abstract

:
Under the trend of vehicle intelligentization, many electrical control functions and control methods have been proposed to improve vehicle comfort and safety, among which the Adaptive Cruise Control (ACC) system is a typical example. However, the tracking performance, comfort and control robustness of the ACC system need more attention under uncertain environments and changing motion states. Therefore, this paper proposes a hierarchical control strategy, including a dynamic normal wheel load observer, a Fuzzy Model Predictive Controller and an integral-separate PID executive layer controller. Firstly, a deep learning-based dynamic normal wheel load observer is added to the perception layer of the conventional ACC system and the observer output is used as a prerequisite for brake torque allocation. Secondly, a Fuzzy Model Predictive Control (fuzzy-MPC) method is adopted in the ACC system controller design, which establishes performance indicators, including tracking performance and comfort, as objective functions, dynamically adjusts their weights and determines constraint conditions based on safety indicators to adapt to continuously changing driving scenarios. Finally, the executive controller adopts the integral-separate PID method to follow the vehicle’s longitudinal motion commands, thus improving the system’s response speed and execution accuracy. A rule-based ABS control method was also developed to further improve the driving safety of vehicles under different road conditions. The proposed strategy has been simulated and validated in different typical driving scenarios and the results show that the proposed method provides better tracking accuracy and stability than traditional techniques.

1. Introduction

With the continuous advancement of smart vehicles, advanced driving assistance systems (ADASs) are being utilized more frequently [1,2,3]. Among its many functions, the Adaptive Cruise Control (ACC) system stands out due to its ability to manage the vehicle’s longitudinal speed and maintain a safe distance from the vehicle in front. This feature reduces the driver’s workload, making it an integral technology in the industry [4,5].
ACC systems typically employ hierarchical control, which is composed of three layers: perception, decision and execution [6,7]. The primary role of the perception layer is to acquire the kinematic information from the vehicle and transmit it to the decision layer. There are two categories of information that this layer processes: relative motion information between the vehicle and the target vehicle (such as inter-vehicle distance and relative velocity) primarily detected via sensors including radar or camera [8]; and the vehicle’s motion state information (e.g., velocity and acceleration), which is typically obtained via onboard sensors. Nonetheless, for commercial vehicles, their high center of gravity and large load characteristics necessitate consideration of the dynamic vertical wheel load influence while designing ACC systems [9]. The most widely used method to estimate dynamic vertical wheel load involves estimating a vehicle model. However, the accuracy of the estimation using this technique is limited by the model’s precision, warranting further discussion on the credibility of the results. The decision layer determines the desired acceleration of the vehicle based on the kinematic information gathered by the perception layer and subsequently commands the execution layer to perform driving or braking operations. Finally, the execution layer includes the driving and braking system that responds to the desired acceleration issued by the decision layer, ultimately enabling the adaptive cruise function.
The operation of Adaptive Cruise Control (ACC) is influenced by various factors such as driving scenarios, engine characteristics and braking system characteristics. It can be reduced to a nonlinear optimal tracking control problem with external disturbance. In the development of the ACC system’s decision layer, several methods are applied, such as PID control, MPC control and fuzzy control. Among them, PID control is favored by the industry due to its low hardware configuration requirements and good control robustness when encountering interference. M. Canale et al. [10] used a robust PI controller to adjust the ACC system response according to a specified speed reference curve. Mahmood, Ali K et al. [11] took into consideration key action parameters of the vehicle and used two PID controllers to adjust the throttle and brake, respectively. Liang, J et al. [12] developed a vehicle acceleration controller based on parallel control theory utilizing the self-learning function of a neural network. However, the PID method requires a considerable amount of parameter adjustment work and cannot achieve optimal control in actual driving scenarios, making it an unsuitable method for ACC control. Model predictive control (MPC) can use future vehicle information for optimal multi-objective control, making it a focal point among researchers. Scholars have proposed various improvements on MPC for ACC, including Zengfu Yang’s [13] algorithm combining MPC and active disturbance rejection control, using feed forward control based on the vehicle dynamic model (VDM) and compensation control based on ADRC to improve control accuracy and suppressing the influence of internal or external disturbance. Li SB [14] uses the feedback-correction method to compensate for prediction error and improve system state prediction accuracy. The constraint-management method was utilized to soften the input/output constraints of the prediction optimization problem by modifying the cost function while avoiding calculation infeasibility caused by large tracking errors. Sangmoon Lee [15] proposed an event-triggered model predictive controller for an Adaptive Cruise Control system utilizing sampled and quantized data. Zeeshan Ali Memon [16] performed a parametric study on the MPC method to assess the response of the ACC system during critical maneuvering times. Even though the existing MPC approach is highly dependent on model accuracy, it still has great potential for improvement. Fuzzy logic has unique advantages in dealing with nonlinear problems, making it an appropriate method for designing the weight factor of the dynamic comprehensive performance index function based on fuzzy rules utilizing model predictive control [17].
Currently, two methods are primarily used for the adaptive cruise execution layer control. One method involves establishing a high-precision longitudinal dynamic model, which requires obtaining several accurate vehicle parameters for dynamic modeling [18,19]. However, changes in external conditions will affect the model’s response, making it challenging to achieve optimal performance. The other method replaces the longitudinal dynamic model with a simple linear model. Although this method is easy to implement, its anti-interference ability is poor and affects control outcomes adversely. To address this problem, this paper proposes using the integral-separated PID approach to realize actual acceleration tracking of desired acceleration [20]. This method avoids system overshoot and oscillation problems, thus enhancing the response speed and accuracy of the actuator layer.
In conclusion, this paper proposes a Fuzzy Model Predictive Control strategy for the Adaptive Cruise Control system based on a dynamic normal wheel load observer. In this control strategy, the observer provides accurate reference for brake force distribution, and the Fuzzy Model Predictive Controller ensures the ACC system’s balance between tracking performance and comfort and adapts to changing driving conditions, while the executive controller ensures the system’s response speed and execution accuracy. Finally, the joint simulation verifies the effectiveness of the observer and ACC system’s control. The main contributions of this paper are as follows:
(1)
In the dynamic normal wheel load observer, Random Forest (RF) is adopted for feature recognition and dimensionality reduction and the processed data are input to the fully connected neural network (FCNN) for estimating the dynamic normal wheel load of the vehicle, which provides a new idea for estimating the vehicle’s dynamic parameters.
(2)
Fuzzy rules are combined with model predictive control methods to overcome the poor adaptability of model predictive control methods to nonlinear problems. The control parameters can be adjusted according to fuzzy rules to adapt to dynamic changes, thereby enhancing the controller’s robustness.
(3)
In the executive layer’s control, the integral-separate PID method is used to avoid oscillation caused by the integral action and enhance the system’s response speed, improving the system’s dynamic performance. The braking safety of the vehicle is further increased by designing a rule-based ABS control method.
The rest of the paper is organized as follows. Section 2 introduces the key component models of the vehicle, including the engine, tire, etc. Section 3 describes the specific control strategy. Section 4 discusses the simulation results, and the key conclusions of the paper are summarized in Section 5.

2. Vehicle and Component Model

This paper focuses on the rear-mounted rear-drive intercity bus, as illustrated in Figure 1. The primary components of the vehicle include the radar, controller, steering system, driving system and braking system. The radar primarily obtains a target vehicle’s relative distance and velocity information. The controller consists of a state observer that detects real-time changes in dynamic vertical wheel load and an ACC system controller. The driving system incorporates the engine control unit (ECU), engine, transmission and other related parts. The braking system includes the air compressor, air storage cylinder, brake controller unit (BCU) and double channel axle modulator (DAM), the pneumatic brake actuator.
The vehicle parameters are shown in Table 1.

2.1. Vehicle Mathematical Model

During vehicle operation, it is necessary to balance the driving torque provided by the vehicle with various resistances, including air resistance, slope resistance and acceleration resistance. The equation expressing the driving force is presented in Equation (1).
T t q i 0 i g η t r = m g sin β + 1 2 C D A ρ v 2 + m g f cos β + δ m v ˙
where m denotes the vehicle mass, v denotes the vehicle longitudinal velocity, T t q denotes the engine torque, η t denotes the transmission efficiency, r denotes the wheel rolling radius, C D denotes the wind resistance coefficient, A denotes the windward area, ρ denotes the air density, f denotes the road rolling resistance co-efficient, β denotes the road grade, δ = 1 + 1 m I w r 2 + 1 m I f i g 2 i 0 2 η t r 2 denotes the rotary mass coefficient, I w denotes the rotating inertia of the wheels, I f denotes the rotating inertia of the flywheel, i 0 denotes the main reduction gear ratio and i g denotes the vehicle transmission ratio.
When the vehicle is in a driving state, based on the current vehicle’s required acceleration, Equation (1) can be transformed into Equation (2) to calculate the required torque of the engine under the current state.
T t q = m g f cos β + 1 2 C D A ρ v 2 + m g sin β + δ m v ˙ r i 0 i g η t

2.2. Engine Model

Establishing an accurate engine model is challenging due to the complexity of its physical characteristics and the numerous factors that affect its working characteristics. In this paper, based on experimental data from a diesel engine, the relationships between engine speed, torque and throttle opening were established, as Figure 2 shows.
During the driving process of the vehicle, Equation (2) can be used to obtain the corresponding driving torque value required for the expected longitudinal acceleration. Then, the value can be processed by looking up the mapping diagram of the engine torque characteristics for the ACC vehicle. By using the known engine torque T t q and engine speed ω e , the throttle opening α d e s required for the expected longitudinal acceleration can be obtained, as shown in Equation (3).
α d e s = f T t q , ω e

2.3. Brake Model

The brake system is comprised of a compressor that serves as a high-pressure air source, a storage cylinder, a double channel axle modulator (DAM) for regulating brake pressure, a brake air chamber, brake calipers and brake discs that convert pressure into brake torque. Pneumatic disc brakes offer several advantages such as a simple structure, lightweight, low noise and fast heat dissipation, which can contribute to improving vehicle active safety. The braking torque on a vehicle equipped with this brake can be computed using Equation (4) as follows:
T b = 2 P b A b η b μ b r b c b .
where P b is braking pressure; A b is braking contact area; η b is braking efficiency; μ b is braking friction coefficient; r b is effective braking radius; c b is brake coefficient. When K b = 2 A b η b μ b r b c b , Equation (4) can be simplified as Equation (5).
T b = K b P b .
where K b is the brake conversion factor, Table 2 gives the brake-related parameter settings in the simulation, the units are all international system units and the brake conversion factor can be calculated as K b = 0.0022 .
Corresponding to the driving state, the braking torque of the vehicle can be expressed as Equation (6).
T b = δ m v ˙ m g f cos β 1 2 C D A ρ v 2 m g sin β r
Given the expected brake torque, the corresponding expected brake pressure value P b can be calculated according to the above formula. By comparing this value with the maximum brake pressure value of the ACC vehicle, the corresponding brake pedal opening value for vehicle deceleration control can be obtained. The calculation of the ACC vehicle’s brake pedal opening is expressed as Equation (7).
β d e s = P b P b max × 100 %
where β d e s is the brake pedal opening, P b is the wheel demand brake pressure and P b max is the upper limit of wheel brake pressure.

2.4. Tire Model

The tire is the sole component of a vehicle that makes contact with the ground and transmits both force and torque. Longitudinal force, lateral force and aligning torque of a vehicle arise from the interaction between the tire and the ground. Therefore, tire model accuracy is essential for creating an accurate vehicle model. Currently, tire models fall into three categories: theoretical, semi-empirical and empirical models. For this paper, the Dugoff tire model was selected to calculate tire force due to its applicability and meeting the required state estimation. The Dugoff tire model equation is shown as Equations (8)–(11).
F x = μ F z × C x λ 1 λ × f ( L ) .
F y = μ F z × C y tan ( α ) 1 λ × f ( L ) .
f ( L ) = L ( 2 L ) , L < 1 1 , L 1
L = ( 1 λ ) 2 C 2 λ 2 + C z 2 tan 2 α × 1 ε × v x × C x 2 λ 2 + C y 2 tan 2 α .
where F x is the longitudinal force of the tire, F y is the lateral force of the tire, F z is the vertical force of the tire, C x and C y are the longitudinal slip stiffness and lateral deflection stiffness of the tire, respectively, α is the lateral slip angle of the tire, λ is the actual longitudinal slip rate and V w is the longitudinal velocity at the wheel center.
The slip rate represents the proportion of sliding to rolling in the vehicle’s overall motion. During braking, the rolling component of the wheel decreases while the sliding component increases as the braking intensity increases. The formula for calculating the longitudinal slip rate is presented in Equation (12).
S r = r r 0 ω w u w u w × 100 % D r i v e u w r r 0 ω w u w × 100 % B r a k e

3. ACC System Control Strategy Development

The ACC system implements a hierarchical control strategy, which consists of three main layers: perception, decision and execution. Figure 3 depicts the logical associations and data transmissions among these layers.
Vehicles equipped with ACC systems, during their driving process, obtain information from the perception layer through vehicle-mounted sensors and state observers. After a determination of the system’s working mode, the vehicle is determined to be in either constant speed cruise mode or follow mode. The PID control method is used for constant speed cruise mode. For follow mode, first the weighting factors applicable to the current scenario are obtained based on preset fuzzy rules and applied to the optimization solution of the objective function. Then, the control quantities obtained from the MPC controller are output and sent to the execution layer, finally achieving the vehicle’s Adaptive Cruise Control function.

3.1. Dynamic Vertical Wheel Load Observer Based on Machine Learning Methods

The dynamic characteristics of vehicles and the mechanical behavior of their tires exhibit strong nonlinearity. The traditional model-based frameworks typically linearize the state equations to compute tire forces, which provide accurate results when the tire is in the linear region, but they are inefficient for nonlinear conditions [21,22]. Consequently, a machine learning-driven method is proposed for estimating vehicle parameters with superior performance in tackling nonlinear problems. The framework shown in Figure 4 consists of three main stages. First, the vehicle travel data is processed and a data model is established. In the second stage, Random Forest (RF) is employed to detect essential features and reduce data dimensions because of the numerous vehicle motion state variables that may lead to high computational loads. Finally, a fully connected neural network (FCNN) is utilized to generate estimates for tire forces.

3.1.1. Data Processing

The output data of vehicle sensors may contain a certain level of noise due to the variation in their sampling frequency and the vibration that occurs during driving. Therefore, it is essential to filter, resample and interpolate the data collected by the vehicle for accurate analysis. One approach to filtering anomalous data points is to use the band-pass filter technique. This method involves combining a high-pass filter and a low-pass filter either in series or parallel, resulting in a filter that permits only signals within a specific frequency range while suppressing signals beyond the cutoff frequency. The transfer function of this filter can be expressed using Equation (13).
h ( s ) = A w o B s s 2 + B s + w o 2 .
where w 0 is the center frequency of the bandpass, A is the passband gain of the filter and B is the bandwidth ratio of the bandpass.
The discretized difference equation for the bandpass filter is shown in Equation (14).
y n = b 0 x n + + b M x n M a 1 y n 1 a N y n N .
where b 0 b M and a 1 a N are the system coefficients, x n is the input signal and y n is the output signal.
To ensure the continuity and smoothness of the data, the method of cubic spline interpolation is used to achieve the unification of different signals in the time and frequency domains, as shown in Equation (15).
S x = a i x 3 + b i x 2 + c i x + d i , x x i , x i + 1 .
where a i , b i , c i , d i are the polynomial coefficients of the i-th interval, which can be obtained by solving a system of linear equations.
The coefficient matrix of the system of linear equations is a tridiagonal matrix that can be solved efficiently via the catch-up method.

3.1.2. RF-Based Feature Selection and Data Dimensionality Reduction

The dataset used for neural network models often involves a considerable number of features, leading to increased complexity and difficulty in optimizing the model. To resolve this issue, the random forest technique can be implemented to remove irrelevant features from the dataset and improve the performance of the model by efficiently selecting critical features as input for the neural network.
During feature selection via the random forest algorithm, the initial dataset is randomized into training and testing sets. The random forest model is subsequently trained on the training set while recording the MDI (Mean Decrease Impurity) score for each feature. During each tree’s training process, a node within the tree randomly selects a subset of samples from its related parent node, forming out-of-bag (OOB) samples. The OOB importance value calculates the accuracy of the model’s prediction performance for each sample. Using the OOB importance scores for individual features, it becomes feasible to select substantial inputs for the neural network. The calculation of the OOB importance score for feature j is expressed in Equation (16).
OOB importance j = 1 B b = 1 B im p j , b .
where B represents the number of trees in the random forest, i m p j , b represents the MDI value of feature j in the b-th tree, which is the information gain brought by using feature j to split in that tree. The OOB standard deviation value of each feature j can also be calculated to evaluate its stability, as shown in Equation (17).
OOB std j = 1 B b = 1 B ( im p j , b OOB importance j ) 2 .
Finally, the features are ranked based on their OOB importance values and standard deviation values and the subset of features with high importance and good stability is selected as the final feature subset.
In the RF feature screening in this paper, the results of the decision tree output were obtained using the mean method and the regression characteristics were obtained as shown in Equation (18).
V F u t u r e = t = 1 T v b P b .
where v b is the information output by the b-th decision tree; P b is the probability distribution of the output speed information of the b-th decision tree.

3.1.3. FCNN-Based Parameter Estimation

Random forest feature selection provides the dataset for regression analysis of dynamic vertical wheel load parameters using a fully connected neural network (FCNN). The structure of the network, as displayed in Figure 5, contains input layers, hidden layers and output layers each with defined neuron count and applied activation functions. The specific hyperparameter settings are shown in Section 4.1.
The dataset is randomly partitioned into two groups consisting of a training set and a validation set. Further, to enhance training stability and rate, the training data require normalization. In this paper, Min-Max Scaling normalization, shown in Equation (19), is utilized.
x n o r m = x x m i n x m a x x m i n
where x is the original data, x m i n and x m a x are the minimum and maximum values in the dataset, respectively, and x n o r m is the scaled data. The range of the scaled data is usually [0,1].
The backpropagation algorithm updates the network parameters during training by using the training set data. The network’s regression performance is evaluated by utilizing the testing set after reducing the training error onto convergence. The parameter regression formula based on the fully connected neural network is demonstrated in Equation (20).
y = f ( W 2 · f ( W 1 · x + b 1 ) + b 2 ) .
In Equation (20), x is the input feature vector, y is the regression output value, W 1 and W 2 are the parameter matrices for the first and second hidden layers, respectively. b 1 and b 2 are bias vectors and f is the ReLU activation function. During the training process, the gradient descent algorithm is used to continuously optimize the parameters W 1 , W 2 , b 1 and b 2 to minimize the difference between the predicted value and the actual value.
It should be noted that this method of observing dynamic vertical wheel loads is not only applicable to highway vehicles, but also to industrial vehicles with relatively simple driving scenarios, such as forklifts. Although these vehicles have lower driving speeds, they can still exhibit changes in wheel normal loads. The observed results of dynamic vertical wheel loads can be applied to the stability issues of forklifts, such as warning of vehicle tip-over [23,24].

3.2. ACC Controller Decision Layer Design

The ACC system comprises a decision layer, which serves as the system’s nucleus. This layer facilitates both intelligent perception and response to complicated traffic conditions and dynamic information throughout car driving. The decision layer’s functionality includes selecting vehicle control modes and outputting expected acceleration levels to the execution layer. It derives this based on the kinematic and dynamic information received from the perception layer. Thus, it reduces the driver’s workload while increasing driving safety and comfort.

3.2.1. System Operating Mode Switching Logic

The operation of the Adaptive Cruise Control (ACC) system involves an initial determination of the current mode of the system. If there are no vehicles detected within the radar range or if the speed of the target vehicle ahead is higher than the speed set by the host vehicle, it operates in constant speed cruise mode. However, if there is a target vehicle ahead, it switches to follow mode. A detailed illustration of this procedure is provided in Figure 6.
The Anti-Windup PID method is used to control the constant speed cruise mode. This involves using the relative speed difference and host vehicle speed as input variables and the desired longitudinal acceleration as the output variable. A saturation function is then applied to the output to limit extreme acceleration values that might otherwise affect ride stability. The primary goal of this function is to maintain vehicle stability and ensure passenger comfort.

3.2.2. ACC System Follows Mode Control Strategy

The implementation of the MPC method for follow mode control necessitates the provision of the state variables needed by the controller through the perception layer. As a result of the vehicle’s inertia, there exists a time lag between the expected acceleration and the current acceleration. To represent the hysteresis properties exhibited by the two accelerations, a primary order inertial link was introduced which is described in Equation (21).
a d e s = τ j ( k ) + a r e a l
where a r e a l is the actual acceleration; j ( k ) is the acceleration change rate; a d e s is the desired acceleration; τ is the first-order inertial link time constant.
In the calculation of the desired relative spacing Δ s ( k ) , Time-To-Collision (in this paper, t h is used to represent TTC) is a crucial parameter [25,26,27]. The physical significance of t h is the time interval for possible collision calculated through the kinematic information between the vehicle and the forward obstacle, as shown in Equation (22). Combined with the current vehicle velocity v h and t h , as well as the preset minimum safe distance Δ s 0 ( Δ s 0 = 5 m), the desired relative spacing Δ s ( k ) can be obtained, as shown in Equation (23).
t h = t h _ max t 0 c v v r e l > t h max t 0 c v v r e l c a a t ; t h min < t 0 c v v r e l c a a t < t h _ max t h min otherwise
Δ s d e s = t h v + Δ s 0
where t 0 , c v , c a are constants greater than zero.
Select real-time relative spacing Δ s ( k ) , longitudinal velocity v h ( k ) , relative speed v r e l ( k ) ( v r e l = v t v h , v t is target vehicle velocity; v h is host vehicle velocity), longitudinal acceleration a h ( k ) and j ( k ) as the state variable. The discrete state space model of the system is established as shown in Equation (24).
x ( k + 1 ) = A x ( k ) + B u ( k ) + G ω ( k ) A = 1 0 T S 1 2 T s 2 0 0 1 0 T S 0 0 0 1 T S 0 0 0 0 1 T S τ 0 0 0 0 1 τ 0 , B = 0 0 0 T S τ 1 τ , G = 1 2 T s 2 0 T S 0 0 , w ( k ) = a t ( k )
where T s is the system sampling period, a t ( k ) is target vehicle acceleration and u ( k ) is the expected acceleration of the ACC system at moment k.
Select the real-time error between the actual and the desired relative spacing δ ( k ) , v r e l ( k ) , a h ( k ) and j ( k ) as the optimized performance target of the ACC control system. This gives y ( k ) = δ ( k ) , v r e l ( k ) , a h ( k ) , j ( k ) T .
Thus, the expression for y ( k ) can be written in the form of Equation (25).
y ( k ) = C x ( k ) Z C = 1 t h 0 0 0 0 0 1 0 0 0 0 0 1 0 0 0 0 0 1 , Z = Δ s 0 0 0 0
The simplified vehicle dynamic characteristics and external interferences can cause errors between the predicted and actual values of the ACC system’s prediction model. These errors can be mitigated through feedback correction, improving the response accuracy and robustness of the system. Equation (26) demonstrates how the prediction error at a given time can be calculated using the feedback-correction principle.
e ( k ) = x ( k ) x p ( k / k 1 ) .
where e ( k ) is the prediction error; x ( k ) is the actual state of the system at the moment k; x p ( k / k 1 ) is the predicted value of moment k 1 for moment k.
Using a weighted matrix to adjust the prediction error to improve the system prediction accuracy, Equation (24) is transformed into Equation (27).
x p ( k + 1 / k ) = A x ( k ) + B u ( k ) + G ω ( k ) + W e ( k ) .
where W = diag w 1 , w 2 , w 3 , w 4 , w 5 , w i ( 0 , 1 ) .
Due to the safety requirements, vehicle performance and road traffic regulations in the working process of the ACC system, the real-time relative spacing Δ s ( k ) , relative velocity v r e l ( k ) and other variables need to be limited within a reasonable range. The constraints are shown in Table 3.
Evaluation indicators for the ACC system include safety, following distance and comfort. Safety refers to maintaining a reasonable distance between front and rear vehicles to prevent collisions. Following distance pertains to matching the speed of the target vehicle and adjusting the actual spacing to the desired level. Comfort involves avoiding rapid acceleration and deceleration during driving. By optimizing control variables and prediction errors while accounting for various performance constraints and evaluation indicators, the ACC system can more effectively track target vehicles. The objective function is displayed in Equation (28).
J = i = 1 p y ^ p ( k + i k ) y r ( k + i ) T Q y ^ p ( k + i k ) y r ( k + i ) + i = 0 m 1 u ( k + i ) T R u ( k + i )
where y ^ p ( k + i k ) is the performance index vector in the prediction time domain; y r ( k + i ) = φ i y ( k ) is the reference trajectory; φ = diag ρ δ , ρ v , ρ a , ρ j , ρ ( 0 , 1 ) ; Q is the following weight coefficient; R is the comfort weight coefficient; p is the prediction time domain; m is the control time domain; u ( k + i ) is the control variable.
From Equation (28), it can be seen that the selection of the following weight coefficient Q and the comfort weight coefficient R will directly affect the performance of the objective function. The following ability refers to the ability of a vehicle equipped with an ACC system to converge to the relative distance error and relative velocity error between itself and the target vehicle, while the comfort weight coefficient affects the control variable u, that is, the host vehicle acceleration. By adjusting Q and R, the system control parameter matching for coping with complicated scenarios can be achieved.
The control matrix constraints of the ACC system are organized as Equation (29).
M ¯ L ¯ X ^ p ( k + p ) N ¯ U ( k + m ) U max U ( k + m ) U min M = Δ s 0 v min a min j min , N = i n f v max a max j max , L = 1 0 0 0 0 0 1 0 0 0 0 0 0 1 0 0 0 0 0 1 , M ¯ = M M M U ( k + m ) = u ( k ) u ( k + 1 ) u ( k + m 1 ) N ¯ = N N N , L ¯ = L 0 0 0 0 L 0 0 0 0 0 0 0 0 L U max = u max u max , U min = u min u min
where i n f stands for infinity, which means there is no upper limit to the relative spacing constraint between the ACC vehicle and the target vehicle.
Based on the above analysis, the multi-objective optimized ACC system control algorithm is turned into an online quadratic optimization problem with constraints as shown in Equation (30).
min U ( k + m ) U ( k + m ) T K 1 U ( k + m ) + 2 K 2 U ( k + m ) s . t . Ω U ( k + m ) T Ω = L ¯ B ¯ L ¯ B ¯ I I , T = N ¯ L ¯ G ¯ ω ( k + p ) L ¯ A ¯ x ( k ) L ¯ W ¯ e x ( k ) M ¯ + L ¯ G ¯ ω ( k + p ) + L ¯ A ¯ x ( k ) + L ¯ W ¯ e x ( k ) U max U min A ¯ = A A 2 A p , B ¯ = B 0 0 A B B 0 A p 1 B A p 2 B A p m B G ¯ = G 0 0 A G G 0 A p 1 G A p 2 G G , H ¯ = H 1 H 2 H p

3.2.3. Fuzzy Control Design Method for Variable Weight Coefficient Design

The effectiveness of Adaptive Cruise Control (ACC) depends on how well it can navigate the complex traffic environment encountered by a vehicle. To ensure control robustness and scenario adaptability in varying driving scenarios, variable system control parameters for ACC are required. This paper proposes the use of a weight factor for the comprehensive performance index function that is updated in real time based on the vehicle’s driving state. The weight factor comprises two components, Q and R, which correspond to the following performance index and comfort performance index, respectively. The comfort performance index weight factor was fixed as R = 1 . However, the online weighting coefficient parameter identification and optimization were performed by adjusting Q. The error between the actual and the desired relative spacing δ ( k ) and relative velocity v r e l ( k ) were used as input variables, whereas Q was utilized as the output variable for fuzzy controller design. Fuzzy linguistic variables were employed to establish the weight factor Q of the followability index, as shown in Equation (31).
δ ( k ) : { NB , NS , ZO , PS , PB } v r e l ( k ) : { NB , NS , ZO , PS , PB } Q : { ZO , PS , PM , PB }
where NB, NS, ZO, PS, PM, PB represent negative big, negative small, zero, positive small, positive medium and positive big, respectively.
In the fuzzy process, the fuzzification range of the real-time error between the actual and the desired relative spacing δ ( k ) is set as [ 30 , 30 ] m and the fuzzification range of relative velocity v r e l ( k ) is set as [ 20 , 20 ] m/s. When Q > 1 , it means that the current driving condition requires a higher following index than the comfort index. Both input variables are designed by using the affiliation function of a triangle. The image of the function is shown in Figure 7.
The change range of Q is set to [ 0 , 5 ] and through analysis it is considered that if the value of Q is at [ 0 , 1 ] , the driving state at that moment is judged to be based on the optimization goal of drive comfort, and if the value is at [ 1 , 5 ] , the driving state at that moment is judged to be based on the optimization goal of vehicle following, so this paper is set in this part to be able to quickly respond to the desired optimization value of the Gaussian-type affiliation function and its affiliation. The function image is shown in Figure 8.
The fuzzy rules designed in this paper are shown in Table 4.
Since the output of the fuzzy controller cannot be directly applied to the actual control, the area-centered method is used to solve the fuzzification calculation to obtain the final value of the followability weighting factor Q and act on the system. The output variable is also plotted about the input variable function surface as shown in Figure 9.

3.3. ACC System Execution Layer Control Method

The execution layer must determine whether the vehicle requires acceleration or deceleration based on the desired acceleration received from the decision layer. It must then convert this desired acceleration into the appropriate actuator commands to achieve the corresponding action. This involves controlling the actuator to apply the required driving torque or braking pressure.

3.3.1. Drive–Brake Switching Logic

In the context of ACC for commercial vehicles, switching between driving and braking states is essential to match the desired acceleration changes. Frequent switching may lead to acceleration oscillation that can affect the actuator, whereas untimely switching can impact the control efficacy of the system. In this research, a rule-based driving–braking switching strategy was implemented. Specifically, the deceleration achieved by the vehicle in a gear-sliding state serves as the threshold value for the driving–braking switching. To simulate the gearbox sliding of the target vehicle, the TruckSim software was used. During the simulation, the throttle opening and braking pressure were set to zero, while the vehicle’s initial speed was set to 120 km/h. The deceleration corresponding to each speed from 0 to 120 km/h was measured and the simulation results were smoothed to derive the driving–braking state switching logic, which is illustrated in Table 5.

3.3.2. Braking Torque Distribution Based on Dynamic Vertical Wheel Load Observation Results

The distribution of vehicle braking force according to the dynamic load of each wheel can make full use of the road friction conditions, thus solving the disadvantage of conservative braking force distribution and ineffective use of road friction that exists in the rule-based braking force-distribution strategy.
When the deceleration demand signal from the ACC system or the brake pedal opening signal from the driver is detected, the braking force-distribution function starts to work. The first step is to calculate the sum of the spring mass of the vehicle, as shown in Equation (32).
F t o t a l = i = 1 4 F z i
The second step is to calculate the braking torque of vehicle demand, as shown in Equation (33).
T t o t a l = r × a × i = 1 4 F z i g
where r is the rolling radius of the wheel.
Finally, the wheel braking force distribution coefficient is calculated, as shown in Equation (34).
λ i = F z i F t o t a l
Therefore, the braking torque of each wheel can be expressed in the form of Equation (35).
T b i = λ i × T t o t a l

3.3.3. Execution Layer PID Control Method

After obtaining the acceleration requirements and braking torque requirements from the decision-making level, the integral-separated PID method is used to control the actuator. The control quantity of the output of the integral-separated PID control can be expressed by Equation (36).
u ( t ) = k p e ( t ) + β k i e ( t ) d t + k d d e ( t ) d t
where β is the switching coefficient of the integral link, β = 1 | e ( k ) | ε 0 | e ( k ) | > ε .
After setting the deviation threshold ϵ , the deviation between the actual torque and the expected torque is judged; if | e | > ϵ , PD control is adopted to cancel the integral link to avoid excessive overshoot and oscillation due to integral accumulation and if | e | > ϵ , PID control is adopted; integral control is introduced to eliminate steady-state error and improve system control accuracy.
In order to improve the control effect of the ACC system in actual driving scenarios, it is necessary to consider the influence of road surface adhesion changes on the performance of the braking system when designing the control method at the execution layer [28,29]. Therefore, a rule-based anti-lock braking system (ABS) control method based on the execution layer is proposed. In ABS control, the wheel motion state is a combination of rolling motion and sliding motion [30,31]. The rule-based ABS control method uses the wheel slip rate as a reference value and applies corresponding pressure-increase, pressure-holding or pressure-reduction commands to the braking system based on the logical operation result of the actual and preset threshold values of the slip rate. This reduces the proportion of sliding motion in the wheel motion and ensures directional stability and safety during vehicle braking.
The proposed rule-based ABS control logic is shown in Figure 10. After obtaining the vehicle speed and wheel speed signals, the slip rate is calculated according to Equation (12). When braking begins, the ABS function will be triggered when the slip rate is greater than 0.4 and the longitudinal vehicle speed is greater than 6 km/h. The ABS controller sends a pressure reduction signal to the brake actuator. When the slip rate is less than 0.1 and the vehicle speed is greater than 6 km/h, the ABS controller issues a pressure-increase control command. If the slip rate is between 0.1 and 0.4, the braking system pressure remains unchanged from the previous moment. ABS control is exited when the vehicle speed is less than 6 km/h.

4. Simulation and Analysis

To verify the effectiveness of the proposed control method, a simulation platform was established utilizing Matlab Simulink and TruckSim. The control strategy design for estimating dynamic vertical wheel load was conducted using Matlab Simulink, which acted as the controller, while the TruckSim vehicle model functioned as the controlled object. Additionally, TruckSim was utilized to generate appropriate driving scenarios essential for the functionality of the ACC system. A diagrammatical representation of the co-simulation platform is illustrated in Figure 11. Notably, all of the simulation and model training operations mentioned in this study were performed on a computer equipped with an Intel i7-12700H processor and 16 GB RAM.

4.1. Dynamic Vertical Wheel Load Observation and Braking Torque Distribution Results

The dataset used in this paper is derived from the results of real vehicle tests conducted with a cooperative enterprise. Stress–strain sensor strips were installed on the suspension of the test vehicle to measure the dynamic vertical load of the wheels, as shown in Figure 12. The electronic stability control (ESC) system of the test vehicle was equipped with a three-axis accelerometer ADXL313, which can measure the acceleration in the X-Y-Z directions of the vehicle. Signals such as engine speed and torque, vehicle speed and wheel speed were all acquired from the vehicle control unit (VCU) through a CANoe device.
This paper collected data for 20 dynamic parameters that change with time during vehicle operation. The parameter list is shown in Table 6.
After filtering and interpolating the data, a random forest algorithm with 500 decision trees and 3 feature nodes was used for feature selection. Eight data items with high weights were eventually selected for dynamic observation of vehicle wheel vertical load. The selected data items are shown in Table 7.
The total size of the dataset is 11,800 groups. The selected data groups were divided into training set, validation set and test set in a ratio of 7:2:1. The normalized data were trained using FCNN network. The specific parameters and training process of the model are shown in Table 8.
To verify the observation accuracy of the vehicle wheel load observer, in the test set, the selected eight types of data were used as inputs to FCNN and the output results were compared and analyzed with the results of the actual vehicle test. Figure 13 and Table 9 show the observed results and estimation accuracy of the dynamic vertical wheel load.
To evaluate the accuracy of the machine learning-based wheel dynamic load observer proposed in this article, a comparative analysis was conducted on the motion parameters of vehicles over a specified period. Figure 13 illustrates the dynamic vertical wheel load observation results. Additionally, Table 9 summarizes the findings obtained from this comparison analysis.
In RMSE and MAE, n denotes the sample size, y i denotes the actual observed value and y ^ i denotes the model predicted value. Smaller values of RMSE and MAE indicate that the predicted value is closer to the true value. The coefficient of determination ( R 2 ) is used to assess the degree of fit of the regression model and a value closer to 1 indicates a better fit. SSR denotes the sum of squared regressions, SSE denotes the sum of squared errors and SST denotes the sum of total squares.
In accordance with the identification results of the dynamic normal wheel load observer, the brake torque of the ACC system is allocated. To verify the control effect of the proposed brake torque allocation method, the results of the brake torque allocation method proposed in this paper are compared with the traditional one based on the fixed proportion of front and rear axles in a single brake scenario ( β d = F B f F B r = 0.55 : 0.45 , F B f , F B r are the maximum braking force of the vehicle front and rear axle brakes, respectively). The comparison of vehicle deceleration and braking distance under the two methods is shown in Figure 14. It should be noted that, to highlight the performance differences between different brake torque allocation methods more significantly, open-loop control is adopted for deceleration in the comparison process. The simulation scenario is set as follows: the initial speed of the vehicle is 80 km/h and the braking begins at 4 s; the required deceleration is 3.5 m/s 2 and the vehicle is released from braking at 8 s.
From Figure 14, it can be seen that the braking force allocation method based on the machine learning dynamic wheel vertical load observer proposed in this paper can effectively improve the vehicle’s braking capability. Compared with the constant proportional braking force allocation method, allocating the braking force based on the vehicle’s dynamic vertical wheel load distribution in open-loop braking scenarios can increase the average deceleration of the vehicle by 18% and shorten the braking distance by 4 m. This significantly improves the utilization rate of road adhesion during the braking process.

4.2. ABS Control Simulation Results

To validate the effectiveness of the proposed rule-based ABS control strategy, a simulation verification of the control strategy was carried out on typical road surfaces. The simulation verification scenario was set up as shown in Table 10.

4.2.1. Low Adhesion Road Simulation Result

The vehicle was subjected to a braking test with an initial speed of 50 km/h on the aforementioned road surface at μ = 0.4 , and simulation results are shown in Figure 15. The trends of wheel speed changes under ABS control were found to be consistent with those of vehicle speed changes. No locking of wheels was observed during the entire braking process and ABS disengaged control when the vehicle speed decreased below 6 km/h. The average slip rate of all four wheels was calculated to be 11.23% during the braking process, indicating the effectiveness of the proposed strategy under low-adhesion road conditions.

4.2.2. Split Road Simulation Result

The vehicle was subjected to a braking test with an initial speed of 50 km/h on the aforementioned split μ road surface, with a low adhesion coefficient of μ = 0.4 on the left side and a high adhesion coefficient of μ = 0.8 on the right side. The simulation results are shown in Figure 16. During the braking process, the average slip rate of the left wheels was found to be 17.43%, with a maximum value of 43.34%, slightly higher than the predetermined threshold value. On the other hand, the average slip rate of the right wheels was 6.14%. No locking of wheels was observed during the entire braking process, demonstrating that the proposed strategy still has a good control effect under the split road conditions.

4.2.3. Bisectional Road Simulation Result

In this section, the road simulation conditions were set to have a road surface adhesion coefficient of μ = 0.8 from 0 to 25 m and a road surface adhesion coefficient of μ = 0.4 after 25 m. The vehicle was subjected to a braking test with an initial speed of 80 km/h and simulation results are shown in Figure 17. When the vehicle reached the boundary between the two road surfaces, there was a significant increase in the slip rate of the front wheels, but it returned to around 20% within 0.3 s. No locking of wheels was observed during the entire braking process, demonstrating that the proposed strategy can still have a certain control effect under harsh bisectional road conditions.

4.3. ACC System Typical Scenario Simulation Result

During vehicle operation, three common scenarios are following a target vehicle, target vehicle insertion and target vehicle braking. These scenarios are utilized to verify the functionality of Adaptive Cruise Control (ACC) systems. The target vehicle scenario is prevalent in high-speed road sections and suburban areas with fewer traffic lights. In this scenario, the ACC system must regulate the vehicle’s speed to smoothly track the target vehicle ahead. The target vehicle insertion scenario requires the ACC system to adjust the vehicle’s longitudinal speed using control strategies to prevent a collision. In the target vehicle braking scenario, the ACC system must promptly brake to avoid collisions. All of these simulation test scenarios compare the Fuzzy Model Predictive Control (MPC) method proposed in this paper with the conventional MPC method that uses fixed weight factors.

4.3.1. Following Target Vehicle

The initial conditions of the simulation of the following target vehicle scenario are set to the target vehicle driving with variable speed according to the sinusoidal wave-form, the initial velocity of the ACC vehicle is 75 km/h, the initial relative distance is 55 m and the initial velocity of the target vehicle is 60 km/h. The simulation results under this scenario are shown in Figure 18.
In the initial stage of the simulation, the actual relative distance is greater than the desired relative distance, but since the velocity of the host vehicle is higher than the target vehicle, it needs to take braking to adjust the velocity of the host vehicle. Therefore, in the first 2 s at the beginning of the simulation, the ACC system focuses more on the followability index, which is reflected in Figure 18c. After this stage, the weight factor Q is stabilized to 1 because the vehicle velocity error and the vehicle distance error gradually converge. According to Figure 18a,b and Table 11, it can be seen that the Fuzzy MPC method has a significant improvement in the control accuracy compared with the normal MPC method.

4.3.2. Target Vehicle Insertion

In the simulation of the target vehicle insertion scenario, the initial conditions of the simulation are set as follows: the initial speed of the ACC vehicle is 60 km/h, the original target vehicle is traveling at 70 km/h in front and the initial distance between the two vehicles is 30 m. At 20 s, the vehicle maintains a constant speed of 60 km/h in the next lane, suddenly cuts in and becomes the new target vehicle, at which time the distance between the host vehicle and the target vehicle is 25 m. The simulation results under this condition are shown in Figure 19.
In the first 20 s after the simulation starts, both the Fuzzy MPC algorithm and the normal MPC algorithm can follow the vehicle in front well. At the 20 s mark, the actual relative distance is less than the desired relative distance and the speed of the host vehicle is higher than the target vehicle due to the cut-in of the front vehicle, which creates a risk of collision between the two vehicles. From Figure 19c, it can be seen that the ACC system can accurately determine the priority of following over comfort in this scenario. It can be seen from Figure 19a,b and Table 12 that the Fuzzy MPC method allows the velocity and relative distance to converge to the desired values more quickly. The time required for the velocity and distance to reach the desired values mentioned in Table 12 refers to the time elapsed after the front vehicle intervenes and starts calculating until the velocity and distance converge again.

4.3.3. Target Vehicle Braking

In the simulation of this scenario, the initial conditions of simulation for the ACC vehicle and the target vehicle are set as follows: the initial speed of the ACC vehicle is 65 km/h. The target vehicle travels at a constant speed of 50 km/h and brakes suddenly at the 17th second with an acceleration of 3 s and then maintains a constant speed. The simulation results under this condition are shown in Figure 20.
In the beginning, the speed of the host vehicle followed the target vehicle and in the 7th second, the speed of the two vehicles converged and the distance between the two vehicles also converged to the expected value. At 17 s, the target vehicle braked suddenly and the ACC system braked and effectively avoided a rear-end collision, ensuring the safety of the vehicle. From Figure 20a,b, it can be seen that the minimum relative distance of the Fuzzy MPC control method is greater than that of the normal MPC, which guarantees a relative distance greater than D e l t a s 0 . From Table 13, it can be seen that the following accuracy and convergence speed of the FMPC method are significantly better than those of the conventional control method. Figure 20c shows that the ACC system has higher requirements for safety when the target vehicle brakes, which follows the design expectation of the controller.

5. Conclusions

This paper proposes a control strategy for the ACC system of commercial vehicles in actual driving scenarios based on machine learning state observers and Fuzzy MPC, aiming to improve its performance. It consists of a vehicle dynamic normal wheel load observer, a Fuzzy Model Predictive Controller and an integral-separate PID executive layer controller. The design based on the machine learning state observer estimates the dynamic normal wheel load parameters during vehicle travel and applies them to the longitudinal dynamic control of the ACC vehicle, determining the prerequisite for brake force allocation based on the estimation results. This allocation method can increase the braking deceleration by 18% under fixed brake pedal opening. The Fuzzy Model Predictive Controller dynamically adjusts control parameters through fuzzy processing of performance index weight factors to ensure system safety. To verify the proposed strategy, a joint simulation platform was established in the TruckSim-Simulink environment and the system performance was simulated and tested in typical scenarios. The results show that the proposed method improves speed-tracking accuracy (RMSE value) by 41.38% and distance-tracking accuracy by 41.31% in the following target vehicle scenario. In the target vehicle insertion scenario, while improving tracking accuracy, the convergence speed of speed and distance tracking is also increased. It can be proved that compared with previous MPC Adaptive Cruise Control strategies, the ACC system control strategy based on machine learning state observer and Fuzzy MPC can respond to changes in vehicle driving scenarios more quickly and stably. The proposed execution layer control method was verified under simulation conditions on a low-adhesion road, a bisectional road and a split road; the results showed that it can handle changing road conditions well and further improve the safety performance of the ACC system.
Future work will focus on two aspects. First, further research will focus on the robustness of the strategy to parameter uncertainties and external disturbances, especially the applicability of the strategy to different vehicle models and its robustness under more detailed driving scenarios (such as vehicle passing over speed bumps). Second, the proposed control strategy will be validated in real-world vehicle tests.

Author Contributions

Conceptualization, J.G. and Y.W.; methodology, software, Y.W. and Z.H.; validation, C.B.; formal analysis, investigation, resources, data curation, writing—original draft preparation, Y.W.; supervision, writing—review and editing, D.Z.; visualization, L.C. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the Changsha Automotive Innovation Research Institute Innovation Project—Research on Intelligent Trip Planning System of Pure Electric Vehicles Based on Big Data (CAIRIZT20220105), the Science and Technology Planning Project in Yibin City (2020GY001), and the Science and Technology Planning Project in Tianjin city (20YFZCGX00770).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interests.

References

  1. Yang, D.; Jiang, K.; Zhao, D.; Yu, C.; Cao, Z.; Xie, S.; Xiao, Z.; Jiao, X.; Wang, S.; Zhang, K. Intelligent and connected vehicles: Current status and future perspectives. Sci. China (Technol. Sci.) 2018, 10, 1446–1471. [Google Scholar] [CrossRef]
  2. Blades, L.; Douglas, R.; Early, J.; Lo, C.Y.; Best, R. Advanced Driver-Assistance Systems for City Bus Applications. SAE Tech. Pap. 2020. [Google Scholar] [CrossRef] [Green Version]
  3. Narkhede, M.M.; Chopade, N.B. Review of Advanced Driver Assistance Systems and Their Applications for Collision Avoidance in Urban Driving Scenario. In Lecture Notes in Networks and Systems; Springer International Publishing: Cham, Switzerland, 2022; pp. 253–267. [Google Scholar]
  4. Xiao, L.; Gao, F. A comprehensive review of the development of Adaptive Cruise Control systems. Veh. Syst. Dyn. 2010, 10, 1167–1192. [Google Scholar] [CrossRef]
  5. He, Y.; Biagio, C.; Zhou, Q.; Michail, M.; Konstantinos, M.; Li, J.; Li, Z.; Yan, F.; Xu, H. Adaptive Cruise Control Strategies Implemented on Experimental Vehicles: A Review. IFAC-PapersOnLine 2019, 5, 21–27. [Google Scholar] [CrossRef]
  6. Yu, L.; Wang, R. Researches on Adaptive Cruise Control system: A state of the art review. Proc. Inst. Mech. Eng. Part J. Automob. Eng. 2022, 2–3, 211–240. [Google Scholar] [CrossRef]
  7. Ardalan, V.; Azim, E. Research Advances in Intelligent Collision Avoidance and Adaptive Cruise Control. IEEE Intell. Transp. Syst. Mag. 2003, 3, 143–153. [Google Scholar]
  8. Ramzi, A.J. ACC Radar Sensor Technology, Test Requirements and Test Solutions. IEEE Trans. Intell. Transp. Syst. 2003, 3, 115–122. [Google Scholar]
  9. Fujio, M.; Keiichi, K.; Kiyoaki, M.; Hitoshi, S.; Toshimichi, T. Gravity center height estimation for the rollover compensation system of commercial vehicles. JSAE Rev. 1999, 4, 493–497. [Google Scholar]
  10. Canale, M.; Malan, S. Robust Design of PID Based ACC S&G Systems. IFAC Proc. Vol. 2003, 18, 333–338. [Google Scholar]
  11. Mahmood, A.K.; Almaged, M.; Noaman, M.N.; Alnema, Y.H. Adaptive Cruise Control of a simscape driveline vehicle model using pid controller. Ournal Eng. Sci. Technol. 2021, 1, 681–695. [Google Scholar]
  12. Liang, J.; Zhao, T.; Xiong, X.; Zhang, W.; Chen, L.; Zhu, N. Design of Vehicle Acceleration Controller Based on Parallel Neural Network PID. Xinan Jiaotong Daxue Xuebao/J. Southwest Jiaotong Univ. 2017, 3, 626–632. [Google Scholar]
  13. Yang, Z.; Wang, Z.; Yan, M. An Optimization Design of Adaptive Cruise Control System Based on MPC and ADRC. Actuators 2021, 6, 110. [Google Scholar] [CrossRef]
  14. Li, S.; Wang, J.; Li, K.; Zhang, D. Study on Robustness and Feasibility of MPC based Vehicular Adaptive Cruise Control System. In Proceedings of the 2009 IEEE Intelligent Vehicles Symposium, Xi’an, China, 3–5 June 2009; Volumes 1 and 2, pp. 1297–1301. [Google Scholar]
  15. Sangmoon, L. Event-triggered MPC for Adaptive Cruise Control System with Input Constraints. Trans. Korean Inst. Electr. Eng. 2017, 1, 165–170. [Google Scholar]
  16. Zeeshan, A.M.; Mukhtiar, A.U.; Dur, M.P. Parametric Study of Nonlinear Adaptive Cruise Control for a Road Vehicle Model by MPC. Mehran Univ. Res. J. Eng. Technol. 2012, 2, 301–314. [Google Scholar]
  17. Gao, Z.; Wang, J.; Hu, H.; Sun, Y. Control mode switching strategy for ACC based on intuitionistic fuzzy set multi-attribute decision making method. J. Intell. Fuzzy Syst. 2016, 6, 2967–2974. [Google Scholar] [CrossRef]
  18. Chen, S.; Chen, H.; Dan, N. Implementation of MPC-Based Trajectory Tracking Considering Different Fidelity Vehicle Models. J. Beijing Inst. Technol. 2020, 3, 303–316. [Google Scholar]
  19. Attila, W.; Viktor, T.; Tamás, T. Framework for Vehicle Dynamics Model Validation. IEEE Access 2022, 10, 35422–35436. [Google Scholar]
  20. Meng, X.; Kou, L.; Yuan, Q.; Pi, Y.; Ke, W. Motion control of robot based on a new integral-separated PID. Int. J. Wirel. Mob. Comput. 2016, 3, 207–213. [Google Scholar] [CrossRef]
  21. Vicente, M.; Steven, E.S. Modeling cooperative and autonomous Adaptive Cruise Control dynamic responses using experimental data. Transp. Res. Part C Emerg. Technol. 2014, 48, 285–300. [Google Scholar]
  22. Song, Y.; Shu, H.; Chen, X. Chassis integrated control for 4WIS distributed drive EVs with model predictive control based on the UKF observer. Sci. China (Technol. Sci.) 2020, 3, 397–409. [Google Scholar] [CrossRef]
  23. Rebelle, J.; Mistrot, P.; Poirot, R. Development and validation of a numerical model for predicting forklift truck tip-over. Veh. Syst. Dyn. 2009, 7, 771–804. [Google Scholar] [CrossRef]
  24. Martini, A.; Bonelli, G.P.; Rivola, A. Virtual testing of counterbalance forklift trucks: Implementation and experimental validation of a numerical multibody model. Machines 2020, 2, 26. [Google Scholar] [CrossRef]
  25. Lenard, J.; Welsh, R.; Danton, R. Time-To-Collision analysis of pedestrian and pedal-cycle accidents for the development of autonomous emergency braking systems. Accid. Anal. Prev. 2018, 115, 128–136. [Google Scholar] [CrossRef] [Green Version]
  26. Li, Y.; Mo, L.; Chen, Q. Differential contribution of velocity and distance to time estimation during self-initiated Time-to-Collision judgment. Neuropsychologia 2015, 73, 35–47. [Google Scholar] [CrossRef]
  27. Nie, X.; Liang, P.; Kazuhiro, O. Autonomous highway driving using reinforcement learning with safety check system based on Time-To-Collision. Artif. Life Robot. 2023, 1, 158–165. [Google Scholar] [CrossRef]
  28. Akhil, C.; Karthik, R.; Shankar, C.S. Analysis of Thresholds in Rule-Based Antilock Braking Control Algorithms. IFAC-PapersOnLine 2020, 1, 404–409. [Google Scholar]
  29. Li, X.; Zhao, L.; Zhou, C.; Li, X.; Li, H. Pneumatic ABS Modeling and Failure Mode Analysis of Electromagnetic and Control Valves for Commercial Vehicles. Electronics 2020, 2, 318. [Google Scholar] [CrossRef] [Green Version]
  30. Koylu, H.; Cinar, A. Development of control algorithm for ABS–suspension integration to reduce rotational acceleration oscillations of wheel. Machines 2018, 3, 1018–1034. [Google Scholar] [CrossRef]
  31. Davide, T.; Fabio, V.; Mathias, M.; Dzmitry, S.; Valentin, I.; Patrick, G.; Ahu, E.H.; Miguel, D.; Aldo, S. An Explicit Nonlinear Model Predictive ABS Controller for Electro-Hydraulic Braking Systems. IEEE Trans. Ind. Electron. 2020, 5, 3990–4001. [Google Scholar]
Figure 1. Vehicle configuration.
Figure 1. Vehicle configuration.
Sensors 23 05722 g001
Figure 2. The map of the engine.
Figure 2. The map of the engine.
Sensors 23 05722 g002
Figure 3. ACC control strategy architecture.
Figure 3. ACC control strategy architecture.
Sensors 23 05722 g003
Figure 4. Logic structure diagram of dynamic vertical wheel load observer.
Figure 4. Logic structure diagram of dynamic vertical wheel load observer.
Sensors 23 05722 g004
Figure 5. FCNN architecture.
Figure 5. FCNN architecture.
Sensors 23 05722 g005
Figure 6. System operating mode switching flowchart.
Figure 6. System operating mode switching flowchart.
Sensors 23 05722 g006
Figure 7. Membership function of each variable. (a) Error between the actual and the desired relative distance δ ( k ) ; (b) Relative velocity v r e l ( k ) .
Figure 7. Membership function of each variable. (a) Error between the actual and the desired relative distance δ ( k ) ; (b) Relative velocity v r e l ( k ) .
Sensors 23 05722 g007
Figure 8. Output variable affiliation function.
Figure 8. Output variable affiliation function.
Sensors 23 05722 g008
Figure 9. Graph of input and output variables.
Figure 9. Graph of input and output variables.
Sensors 23 05722 g009
Figure 10. Flow chart of rule-based ABS control method.
Figure 10. Flow chart of rule-based ABS control method.
Sensors 23 05722 g010
Figure 11. Control strategy simulation platform architecture.
Figure 11. Control strategy simulation platform architecture.
Sensors 23 05722 g011
Figure 12. Wheel dynamic vertical load sensor installation diagram.
Figure 12. Wheel dynamic vertical load sensor installation diagram.
Sensors 23 05722 g012
Figure 13. Dynamic vertical wheel load observation results. (Taking the left front wheel of the vehicle as an example.) (a) Observations of actual vehicle driving data over a period of time; (b) Single braking condition; (c) Single brake condition observation result.
Figure 13. Dynamic vertical wheel load observation results. (Taking the left front wheel of the vehicle as an example.) (a) Observations of actual vehicle driving data over a period of time; (b) Single braking condition; (c) Single brake condition observation result.
Sensors 23 05722 g013
Figure 14. Validation results of brake force distribution strategy. (a) Comparison of braking torque distribution; (b) Comparison of braking deceleration and braking distance results.
Figure 14. Validation results of brake force distribution strategy. (a) Comparison of braking torque distribution; (b) Comparison of braking deceleration and braking distance results.
Sensors 23 05722 g014
Figure 15. Simulation results of ABS strategy under low adhesion conditions. (a) Vehicle speed and wheel speed curves; (b) Wheel slip rate curves.
Figure 15. Simulation results of ABS strategy under low adhesion conditions. (a) Vehicle speed and wheel speed curves; (b) Wheel slip rate curves.
Sensors 23 05722 g015
Figure 16. Simulation results of ABS strategy under split road conditions. (a) Vehicle speed and wheel speed curves; (b) Wheel slip rate curves.
Figure 16. Simulation results of ABS strategy under split road conditions. (a) Vehicle speed and wheel speed curves; (b) Wheel slip rate curves.
Sensors 23 05722 g016
Figure 17. Simulation results of ABS strategy under bisectional road conditions. (a) Vehicle speed and wheel speed curves; (b) Wheel slip rate curves.
Figure 17. Simulation results of ABS strategy under bisectional road conditions. (a) Vehicle speed and wheel speed curves; (b) Wheel slip rate curves.
Sensors 23 05722 g017
Figure 18. Simulation results of following target vehicle scenario. (a) Vehicle velocity simulation results; (b) Relative distance simulation results; (c) Curves of weight coefficient Q versus time and velocity and relative distance.
Figure 18. Simulation results of following target vehicle scenario. (a) Vehicle velocity simulation results; (b) Relative distance simulation results; (c) Curves of weight coefficient Q versus time and velocity and relative distance.
Sensors 23 05722 g018
Figure 19. Simulation results of target vehicle insertion scenario. (a) Vehicle velocity simulation results; (b) Relative distance simulation results; (c) Curves of weight coefficient Q versus time and velocity and relative distance.
Figure 19. Simulation results of target vehicle insertion scenario. (a) Vehicle velocity simulation results; (b) Relative distance simulation results; (c) Curves of weight coefficient Q versus time and velocity and relative distance.
Sensors 23 05722 g019
Figure 20. Simulation results of target vehicle braking scenario. (a) Vehicle velocity simulation results; (b) Relative distance simulation results; (c) Curves of weight coefficient Q versus time and velocity and relative distance.
Figure 20. Simulation results of target vehicle braking scenario. (a) Vehicle velocity simulation results; (b) Relative distance simulation results; (c) Curves of weight coefficient Q versus time and velocity and relative distance.
Sensors 23 05722 g020
Table 1. Vehicle parameters.
Table 1. Vehicle parameters.
ParameterUnitValue
Vehicle masskg11,550
Wheelbasemm5500
Front wheel trackmm2080
Rear wheel trackmm1870
Wheel rolling radiusmm530
Frontal aream 2 7.5
Engine maximum powerkW323
Table 2. Brake-related parameter setting.
Table 2. Brake-related parameter setting.
ParameterUnitValue
A b m 2 0.005
η b -0.99
μ b -0.25
r b m0.3
c b -3
Table 3. ACC System Constraints.
Table 3. ACC System Constraints.
Constraint NameConstraint Expressions
Safety Δ s ( k ) Δ s 0
Following δ ( k ) 0 , v r e l ( k ) 0 , w h e n ( k )
Comfortability j C min j C ( k ) j C max
Velocity restraints v min v ( k ) v max
Control variable constraint u min u ( k ) u max
Table 4. Fuzzy control rules table.
Table 4. Fuzzy control rules table.
δ ( k ) / v rel ( k ) NBNSZOPSPB
NBPBPBPBPBPM
NSPBPBPBPMPS
ZOPMPMPSPSZO
PSPMPSZOZOZO
PBPSPSZOZOZO
Table 5. Driving–braking switching logic.
Table 5. Driving–braking switching logic.
Switching LogicVehicle State
a d e s a + Δ h Driving
a d e s a Δ h Braking
a Δ h < a d e s < a + Δ h Keep the original state
Table 6. Original data classification.
Table 6. Original data classification.
NumberParameter NameNumber of Parameters
1Engine speed and torque2
2Front wheel turning angle1
3Transmission ratio1
4Wheel brake pressure4
5Wheel speed4
6Wheel slip rate4
7Vehicle longitudinal acceleration1
8Sprung mass vertical velocity1
9Yaw rate1
10Longitudinal vehicle speed1
Table 7. Selected data items.
Table 7. Selected data items.
NumberParameter NameNumber of Parameters
1Engine speed and torque2
2Wheel brake pressure4
3Vehicle longitudinal acceleration1
4Sprung mass vertical velocity1
Table 8. Detailed Parameter Setting.
Table 8. Detailed Parameter Setting.
Parameter NameValueParameter NameValue
Number of hidden layers2Traning epoch1000
Number of hidden layer nodes128/64Training set size8260
Learning rate1 × 10 4 Validation set size2360
Batch size128Testing set size1180
OptimizerADAMWeight decay1 × 10 4
Table 9. Accuracy analysis of observation results.
Table 9. Accuracy analysis of observation results.
Evaluation CriteriaCalculation FormulaCalculation Results
RMSE R M S E = 1 n i = 1 n ( y i y ^ i ) 2 320.04/N
MAE M A E = 1 n i = 1 n | y i y ^ i | 107.41/N
R 2 R 2 = S S R S S T = 1 S S E S S T 0.9997
Table 10. ABS simulation conditions.
Table 10. ABS simulation conditions.
Road SettingInitial Speed
Low adhesion road50 km/h
Split road50 km/h
Bisectional road80 km/h
Table 11. Comparison of the control accuracy of different methods of following target vehicle scenario.
Table 11. Comparison of the control accuracy of different methods of following target vehicle scenario.
Normal MPCFuzzy MPCPerformance Enhancement
Velocity RMSE3.80 km/h2.23 km/h41.38%
Relative distance RMSE3.72 m2.18 m41.31%
Table 12. Comparison of the control accuracy of different methods of target vehicle insertion scenario.
Table 12. Comparison of the control accuracy of different methods of target vehicle insertion scenario.
Normal MPCFuzzy MPCPerformance Enhancement
Velocity RMSE6.82 km/h6.04 km/h11.38%
Relative distance RMSE6.37 m5.98 m6.31%
Time required for velocity to reach reference value25.55 m12.16 m13.39 s
Time required for distance to reach reference value24.83 m16.25 m8.58 s
Table 13. Comparison of the control accuracy of different methods of target vehicle braking scenario.
Table 13. Comparison of the control accuracy of different methods of target vehicle braking scenario.
Normal MPCFuzzy MPCPerformance Enhancement
Velocity RMSE6.36 km/h5.69 km/h10.57%
Relative distance RMSE4.82 m3.20 m33.62%
Time required for velocity to reach reference value9.07 m5.23 m3.84 s
Time required for distance to reach reference value14.64 m12.11 m2.53 s
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

Guo, J.; Wang, Y.; Chu, L.; Bai, C.; Hou, Z.; Zhao, D. Adaptive Cruise System Based on Fuzzy MPC and Machine Learning State Observer. Sensors 2023, 23, 5722. https://doi.org/10.3390/s23125722

AMA Style

Guo J, Wang Y, Chu L, Bai C, Hou Z, Zhao D. Adaptive Cruise System Based on Fuzzy MPC and Machine Learning State Observer. Sensors. 2023; 23(12):5722. https://doi.org/10.3390/s23125722

Chicago/Turabian Style

Guo, Jianhua, Yinhang Wang, Liang Chu, Chenguang Bai, Zhuoran Hou, and Di Zhao. 2023. "Adaptive Cruise System Based on Fuzzy MPC and Machine Learning State Observer" Sensors 23, no. 12: 5722. https://doi.org/10.3390/s23125722

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