Next Article in Journal
Numerical Investigation of Effect of Structural Parameters on the Performance of a Combustion-Driven Sparkjet Actuator
Previous Article in Journal
Characteristic Analysis of a New Structure Eccentric Harmonic Magnetic Gear
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Hierarchical Control Scheme for Adaptive Cruise Control System Based on Model Predictive Control

1
State Key Laboratory of Automotive Safety and Energy, Tsinghua University, Beijing 100084, China
2
School of Engineering and Technology, China University of Geosciences, Beijing 100083, China
*
Author to whom correspondence should be addressed.
Actuators 2023, 12(6), 249; https://doi.org/10.3390/act12060249
Submission received: 19 May 2023 / Revised: 9 June 2023 / Accepted: 13 June 2023 / Published: 14 June 2023
(This article belongs to the Section Control Systems)

Abstract

:
An adaptive cruise control (ACC) system can improve safety and comfort during driving by taking over longitudinal control of the vehicle. It requires the coordination between the upper-layer controller and the lower-layer actuators. In this paper, a hierarchical anti-disturbance cruise control architecture based on electronic stability control (ESC) system is proposed. The upper-layer controller outputs the desired longitudinal acceleration or deceleration to the lower-layer actuators. In order to improve the accuracy of model prediction and achieve the coordinated control of multiple objectives, an upper-layer model prediction cruise controller is established based on feedback control and disturbance compensation. In addition, based on the hydraulic control unit (HCU) model and the vehicle longitudinal dynamics model, a lower-layer nonlinear model predictive deceleration controller is proposed in order to solve the problems of pressure fluctuations and the low accuracy of small decelerations when ESC is used as the actuator for the ACC system. Finally, the simulation and experimental tests were carried out. The results show that the proposed control architecture can improve the stability and comfort of the cruise control process. Moreover, compared with the traditional PID deceleration controller, it effectively improves the deceleration control accuracy.

1. Introduction

With the continuous progress of automotive technology, people have increasingly high requirements for automotive safety and comfort. The adaptive cruise control (ACC) system is one of the most advanced driving assist systems (ADAS) that helps the driver by taking over the accelerator and brake pedals, automatically controlling the relative speed and distance between the ego vehicle and the front vehicle [1,2]. Not only does it effectively improve the safety and comfort of the driving process but also traffic efficiency [2,3,4,5,6]. ACC systems mostly adopt a hierarchical control algorithm. The upper-layer controller senses the traffic situation ahead through sensors, such as radar and cameras; judges the required longitudinal acceleration; and sends the command to the lower-layer drive-by-wire (DBW) system and brake-by-wire (BBW) system for longitudinal dynamics control [7].
The upper-layer controller for ACC systems have been studied since the 1960s, and researchers have designed various cruise controllers. Zhang and Pradhan et al. [8,9] designed the traditional PID controller to adjust the relative speed and relative distance during cruise. Chaturvedi et al. [10] designed an optimized PID controller based on particle swarm optimization technology and teaching–learning optimization technology, which reduces the overshoot rate and the rise time of the system. Sawant et al. [11] proposed a sliding mode controller based on the disturbance observer to control the ACC system to overcome the model disturbance and analyzed the stability of the system. Li et al. [12] designed a terminal sliding mode controller, which improves the robustness of the cruise controller to modeling uncertainties and external disturbances and improves the convergence rate of the system. In recent years, in order to achieve multi-objective coordinated control, the model predictive control (MPC) has been applied to cruise controllers. Ma and Nie et al. [13,14] established an ACC controller based on MPC, which considered various constraints, such as economy, safety, and comfortability characteristics, and was proven to improve economic efficiency through simulation. Xu et al. [15] proposed a novel ACC strategy based on a hierarchical framework, established a sliding acceleration identification model to improve the robustness of the upper-layer MPC controller and built an iterative learning lower-layer controller to reduce vehicle speed fluctuations.
Most of the BBW systems currently used in passenger cars are electronic stability control (ESC) systems, which are often used as the actuators for ADAS, such as the ACC system. The hydraulic control unit (HCU) of ESC is mainly composed of solenoid valves, coil, plunger pumps, and DC motors [16,17]. The most common method is to use pulse width modulation (PWM) to control the motor and the coil to drive the plunger pump and solenoid valve, respectively. By adjusting the hydraulic pressure of the wheel cylinder, the longitudinal deceleration of the vehicle can be controlled. However, HCU has highly nonlinear characteristics, and there are problems such as pressure overshoot and noise.
Early wheel cylinder pressure (WCP) controllers generally used the PID method to control the duty cycle of the solenoid valve [18], but there were problems in pressure overshoot and rapidity. Certain improved PID control methods have recently been developed. In recent years, with the research on the model of HCU, researchers have proposed a series of novel controllers. Meng and Fang et al. [19,20] established the mathematical model of the key components of HCU and analyzed the impact of component parameters on brake pressure control using simulation and experimental methods. Han et al. [21] proposed a sliding mode pressure controller based on a pressure estimator to track the desired pressure without pressure sensors. Zhao and Braun et al. [22,23] realized the observation of solenoid valve spool position and WCP control based on the sliding mode observer and controller. Zhao et al. [24] established a pressure controller for commercial vehicles based on the MPC theory and carried out a simulation and experimental verification.
This paper takes passenger cars as the research object and designs a hierarchical cruise controller scheme. Considering the interference of vehicle parameters, sensor measurement errors, road disturbances, and other factors during driving, combined with the principles of feedback control and disturbance compensation, a robust upper-layer MPC controller is proposed for coordinating multiple control objectives. In addition, according to the physical model of HCU and the vehicle dynamics, a lower-layer deceleration controller is proposed based on nonlinear model predictive control (NMPC), which controls the duty of the motor and the coil, respectively, and realizes the precise hydraulic pressure adjustment of the wheel cylinder.
The structure of this paper is organized as follows. In Section 2, the cruise system model, vehicle dynamics model, and BBW system model are presented. In Section 3, the hierarchical control architecture of the ACC system is designed based on the MPC theory. In Section 4, the simulation and experiment are carried out to verify the effectiveness of the proposed method. Finally, the conclusions are given in Section 5.

2. System Modeling

2.1. Adaptive Cruise Control System Modeling

During the cruise process, the kinematic relationship between the ego vehicle and the front vehicle is shown in Figure 1. vego and aego represent the velocity and acceleration of the ego vehicle, respectively. vo and ao represent the velocity and acceleration of the front vehicle, respectively. xrel is the relative distance between the two vehicles.
The kinematic relationship between the ego vehicle and the front vehicle can be described as follows:
x e = x d e s x r e l v e = v o v e g o
where xdes represents the desired distance between two vehicles. xe and ve represent the distance error and the velocity error, respectively. The desired velocity of the ego vehicle is vo.
During the cruising process, based on the constant time headway Th, the desired distance xdes can be calculated as follows [25]:
x d e s = v e g o T h + d s a f e
where dsafe is the safe distance when the ego vehicle stops.
Considering the delay characteristics of the vehicle drive system [26], the relationship between the actual longitudinal acceleration aego and the desired longitudinal acceleration ades is approximately considered to be a first-order system, and its discretization expression is described as follows:
a e g o k + 1 = τ τ + T s a e g o k + T s τ + T s a d e s k
where τ is the time delay coefficient, Ts is the sampling time.
Selecting x(k) = [xe(k) vrel(k) aego(k)]T as the state vector of the longitudinal vehicle model and u = ades(k) as the input vector, the discrete-time state space equation of ACC system can be established as follows:
x k + 1 = A x k + B u k + Γ d k y k = C x k d k = a 0 k
where A = 1 T s T h T s 0 1 T s 0 0 1 T s / τ B = 0 0 T s / τ C = 1 0 0 0 1 0 Γ = 0 T s 0 .

2.2. Vehicle Longitudinal Dynamics Modeling

Neglecting the influence of the tire slip and considering that the slope angle is very small when the vehicle is running normally, the equation for the longitudinal dynamics of a vehicle can be obtained as follows [27]:
δ m a e g o = T t q i g i 0 η T r P w K P r G f G i 1 2 C D A ρ a v e g o 2
where δ represents the rotational mass coefficient; m represents the mass of vehicle; Ttq represents the engine torque; ig and i0 are the gear ratios of the transmission and main retarder, respectively; ηT represents the efficiency of the transmission system; r is the radius of the wheel; G is the gravity of the vehicle; f is the rolling resistance coefficient; i is the slope of the road; CD is the air resistance coefficient; A is the windward area of the vehicle; ρa is the air density; Pw is the WCP; and KP is a gain coefficient.

2.3. Hydraulic Control Unit Modeling

2.3.1. Wheel Cylinder and Braking Pipeline Model

Passenger vehicles generally adopt a hydraulic disc braking system, and the HCU is the main part that realizes WCP control. The two hydraulic circuits in the HCU have the same structure and are connected to the two oil outlets of the master cylinder, respectively. Taking one hydraulic circuit of the HCU as an example, its structural diagram is shown in Figure 2, in which the isolate valve (IV) and the apply valve (AV) are normally open, and the prime valve (PV) and release valve (RV) are normally closed. During the pressurization process, the PV is energized to open, the IV is energized to close, and the motor is energized to drive the plunger pump to pump the brake fluid from the low-pressure area into the high-pressure area. During the decompression process, only the IV is energized to control the brake fluid from the high-pressure area to the low-pressure area with a certain duty. During the pressure maintenance process, only the IV is energized to close and maintain the pressure of the high-pressure area.
Neglecting the compressibility of brake fluid, the relationship between WCP and the flow rate of the brake fluid can be described as follows:
P ˙ w t = K Q r f p Q v
where K is the volumetric stiffness of the wheel cylinder; Qrfp and Qv are the volumetric flow rate flowing in from the plunger pump and the volumetric flow rate flowing out from the IV, respectively.

2.3.2. Motor and Plunger Pump Model

The schematic diagram of the positional relationship between the motor and the plunger pump is shown in Figure 3. The motor drives the plunger pumps symmetrically distributed on both sides via the eccentric camshaft. Point O is the rotation center of the camshaft whose eccentricity is d0. d is the inner diameter of the plunger, and θ is the rotation angle of the motor shaft. Within a working cycle, the plunger reciprocates once to achieve the suction and pumping of brake fluid.
The motor is a permanent magnet DC motor, and its speed characteristics can be described as follows:
n = U a C e Φ R a C e C T Φ 2 T L + T 0
where n is the speed of the motor; Ua is the input voltage of the motor; Ce and CT are the electromotive force constant and torque constant, respectively; Ra is the armature circuit resistance; Φ is the magnetic flux; TL is the load torque; and T0 is the no-load torque.
According to the positional relationship between the plunger pump and the motor, and ignoring the torque fluctuation in each cycle, the load torque can be calculated as follows:
T ¯ L = P w d 2 d 0
where Pw is the outlet pressure of the plunger pump, which is equal to the WCP.
Considering the leakage of the plunger pump and ignoring the flow fluctuation in each cycle, the corrected average flow rate of the plunger pump is calculated as follows:
Q r f p = π 120 d 2 d 0 n η v = π 120 d 2 d 0 η v U a C e Φ P w d 2 d 0 R a C e C T Φ 2 R a T 0 C e C T Φ 2
where ηv represents the efficiency of the plunger pump.
According to (7)–(9), the average flow rate of a single plunger pump can be described as follows:
Q r f p = f p U a , P w

2.3.3. Solenoid Valve and Coil Model

The structure of the IV is shown in Figure 4, and the coil is set outside the magnetic isolation tube of the IV. The spool of the IV is subjected to multiple forces, such as the electromagnetic force, spring force, and hydraulic force, etc. [28]. Only the electromagnetic force can be controlled by the current of the coil.
The current response time of the electromagnetic coil and the response time of the spool movement are obviously shorter than the coil voltage control cycle. Therefore, ignoring the coil inductance and the counter electromotive force generated by the movement of the spool, the relationship between the coil current i and the input voltage Uc is shown as follows:
U c = i · R
where R is the coil resistance.
Neglecting the viscous force and friction force during the movement of the spool, the kinetic equation of the spool can be obtained as follows:
z ¨ = 1 m s F m F s F k
where z is the displacement of the spool, z = 0 mm when the spool is in contact with the valve seat, and the IV is fully closed. ms is the mass of the spool, and Fm, Fs, and Fk represent the electromagnetic force, hydraulic force, and spring force on the spool, respectively.
According to Maxwell’s equations, the main air gap reluctance and secondary air gap reluctance are mainly considered, and the electromagnetic force can be calculated as follows [28]:
F m = ψ i , z 2 2 μ 0 S 0 = i 2 · N 2 2 μ 0 S 0 z + z 0 π μ 0 S 0 + ln r 1 / r 2 2 π μ 0 l n
where ψ(i,z) represents the flux linkage, μ0 is the vacuum permeability, S0 is the area of air gap; N is the number of turns of coil; z0 is the length of the main air gap when the IV is fully closed. r1 and r2 represent the radius of the armature and the secondary air gap, respectively; ln represents the width of the secondary air gap.
In order to calculate the hydraulic force on the spool, the control volume is selected as shown in Figure 5. Applying Reynolds transport theorem, the hydraulic force can be calculated as follows [29]:
F s = ρ v Q v v 0 ρ v Q v v 1 cos α + P 0 A 0 + c P 1 A t sin α P 1 A 1 cos α
where A0, A1, and At are the area of the valve inlet section, the valve throttle, and valve seat, respectively, and A2 is the area of the valve outlet; and P0, P1, and P2 are the pressures at A0, A1, and A2, respectively. Assume that under the pressurization condition, P0 is equal to PW and P2 is 0. v0 and v1 are the average velocity of the fluid at A0 and A1, respectively. ρv is the density of the brake fluid; Qv is the flow rate flowing through the IV; α is the half-cone angle of the valve seat; and c is the correction coefficient for uneven pressure distribution at At.
Based on the geometric structure, each area can be calculated as follows:
A 0 = π 4 d v 2 A 1 = π z 2 sin 2 α cos α + 2 R s z sin α cos α A t = π R s + z sin α 2 cos 2 α sin α d v 2 4 sin α
where Rs is the radius of the ball at the top of the spool, and dv is the inlet diameter of the valve seat.
Define ΔP = P0P2 as the pressure drop across the valve. Calculate the valve flow rate according to the orifice throttling formula as follows:
Q v = c d A 1 2 Δ P / ρ v
where cd is the flow coefficient of the valve.
According to the Bernoulli equation and continuity principle, we can obtain:
Q v = A 0 v 0 = A 1 v 1 = A 2 v 2
P 1 = P 2 + c d 2 Δ P 1 + ζ A 1 2 A 2 2 1
where ζ is the energy dissipation coefficient of the valve.
Considering that A1 is much smaller than A2, the pressure at the valve throttle can be calculated as follows:
P 1 = P 2 c d 2 Δ P
Substituting (16)–(19) into (14), the steady-state hydrodynamic forces can be obtained as follows:
F s = P 0 2 c d 2 A 1 2 A 0 c d 2 A 1 cos α c c d 2 A t sin α + A 0
The spring force on the spool can be calculated as follows:
F k = F 0 K k z
where Kk is the spring stiffness, F0 is the spring force when the IV is fully closed.
As mentioned above, the response time of the spool movement is much shorter than the coil voltage control cycle. Therefore, assuming that the spool acceleration z ¨ = 0 , substituting (13), (20) and (21) into (12), the spool displacement z(Uc, Pw) can be obtained. Then, according to (16), the flow rate Qv can be obtained as follows:
Q v = c d A 1 z U c , P w 2 P w ρ = f v U c , P w

3. Controller Design

The ACC controller adopts a hierarchical control structure, as shown in Figure 6, including an upper-layer controller and a lower-layer controller. The upper-layer controller calculates the desired acceleration ades of the vehicle according to the current motion state of the vehicle and the relative motion state with the front vehicle and transmits it to the lower-layer controller. According to the instructions of the upper-layer controller, the lower-layer controller controls the engine torque through the interface of the engine management system (EMS) and adjusts the WCP by controlling the HCU to realize the tracking of the desired acceleration ades.

3.1. The Design of the Upper-Layer Controller

In the car-following process, changes in a vehicle’s mass, road surface, and other conditions will have a certain impact on the accuracy of the model prediction, and the measurement accuracy of the sensor will also lead to a certain error. In order to improve the robustness of system, the feedback correction method is applied to the MPC controller.
According to the system state measurement value x(k) at time k and the one-step system state prediction value x(k|k − 1) at time k − 1, construct the system state prediction error as follows:
e k = x k x k | k 1
Define a new system state variable χ(k) = [x(k) u(k − 1)]T, the augmented state-space equation with feedback correction term can be obtained as follows:
χ k + 1 = A ˜ χ k + B ˜ Δ u k + Γ ˜ d k + H ˜ e k γ k = C ˜ χ k
where A ˜ = A B 0 I , B ˜ = B I , C ˜ = C 0 , Γ ˜ = Γ 0 , H ˜ = H 0 , Δ u k = u k u k 1 , H is the feedback correction coefficient matrix, and I is the identity matrix.
Define the prediction time domain of the MPC controller as p, and the control time domain as m, the system prediction model with feedback correction items can be obtained as follows:
Z = S χ χ k + S Δ U Δ U + S d d k + S e e k
where Z = γ k + 1 γ k + m γ k + p , S χ = C ˜ A ˜ C ˜ A ˜ m C ˜ A ˜ p , S d = C ˜ Γ ˜ i = 0 m 1 C ˜ A ˜ i Γ ˜ i = 0 p 1 C ˜ A ˜ i Γ ˜ , S e = C ˜ H ˜ C ˜ A ˜ m 1 H ˜ C ˜ A ˜ p 1 H ˜ , S Δ U = C ˜ B ˜ 0 0 C ˜ A ˜ m 1 B ˜ C ˜ A ˜ m 2 B ˜ C ˜ B ˜ C ˜ A ˜ p 1 B ˜ C ˜ A ˜ p 2 B ˜ C ˜ A ˜ p m B ˜ , Δ U = Δ u k Δ u k + m 1 Δ u k + p 1 .
Considering the tracking capability and comfort of the ACC system comprehensively, the multi-objective cost function JACC is designed as follows [30]:
J A C C Z , Δ U = Z Z r e f T Q Z Z r e f + Δ U T R Δ U
where Zref is the reference value of the system state, and Q and R are the weight coefficient matrices of the predicted output and system control input, respectively.
The vehicle’s BBW system and engine system limit the vehicle’s dynamic response characteristics, such as maximum speed, maximum acceleration, etc. In addition, the safety objective of the ACC system, as well as the riding comfort of the driver and passengers should also be considered. In summary, the optimization problem of the upper controller of the ACC system under the constraints can be described as follows:
min Δ U J A C C Z , Δ U s . t . u min u u max Δ u min Δ u Δ u max γ min γ γ max
where umin and umax and Δumin and Δumax are the upper and lower limits of the expected acceleration and the control output change rate, respectively. γmin and γmax are the upper and lower limits of each state variable, such as the distance error and the velocity error.

3.2. The Design of the Lower-Layer Controller

As the lower-layer actuators system, the DBW system and BBW system are used to accurately execute the desired longitudinal acceleration calculated by the upper-layer controller. However, changes in external conditions, such as changes in road conditions and changes in air resistance caused by vehicle speed, make it difficult for the actuator system to track the required deceleration accurately. In addition, the BBW system using ESC has strong nonlinear characteristics, which also increases the difficulty of control. In order to achieve precise control of vehicle acceleration and deceleration, a nonlinear model predictive controller (NMPC) is designed in this section to control the engine torque and the duty of the IV and the motor in coordination.
When the desired longitudinal acceleration is positive, the WCP is zero, and the desired engine torque Ttq,des can be calculated according to (5) as follows:
T t q , d e s = δ m a d e s + G f + G i + 1 2 C D A ρ a v e g o 2 i g i 0 η T r
For the desired engine torque Ttq,des, it can be directly controlled using the torque interface opened by EMS to ESC. Good control performance can be achieved by using a PID controller. It is not the research focus of this paper and will not be described further.
When the desired longitudinal acceleration is negative, the engine output torque is zero. Combining (5) and (6), the desired WCP Pw,des can be calculated as follows:
P w , d e s = δ m a d e s G f G i 1 2 C D A ρ a v e g o 2 K P r
When the actual deceleration is less than the expected deceleration, the ESC is in the pressurization process, and the duty of plunger pump motor needs to be controlled. Select the system state variable x = Pw, the control input up = Ua, and the Euler method is used to discretize the continuous-time system defined by (10), the discrete time state-space equation can be obtained as follows:
x k + 1 = f p x k , u p k
When the actual deceleration is greater than the expected deceleration, the ESC is in the decompression process, and the duty of the IV needs to be controlled. Select the system state variable x = Pw, the control input uv = Uc, and the Euler method, which is used to discretize the continuous-time system defined by (22), and the discrete-time state-space equation can be obtained as follows:
x k + 1 = f v x k , u v k
The multiple objectives in the deceleration control process include accuracy, rapidity, stability, etc., and the multi-objective optimization function JDEC at time k is designed as follows:
J D E C x k , U k = i = 1 N p x k + i r k + i L 2 + i = 1 N c 1 u k + i u r k + i M 2
where r and ur are reference values of system states and input and L and M are weight coefficient matrices.
Considering the limitations of the power supply of the vehicle chassis system and equipment, such as wheel cylinders, in summary, the optimization problem of the lower-layer deceleration controller of the ACC system under the constraints can be described as follows:
min U k J D E C x k , U k s . t . U min U U max Δ U min Δ U Δ U max x min x x max
where Umin and Umax and ΔUmin and ΔUmax are the upper and lower limits of the vehicle supply voltage and its change rate, respectively. xmin and xmax are the upper and lower limits of WCP.

4. Simulation and Experiment

In order to verify the performance of the proposed ACC algorithm, a joint simulation platform of Carsim-MATLAB/Simulink was built, and a variety of test scenarios were selected for simulation. The simulation parameters are chosen as follows: the sampling interval is selected to be 0.1 s, the prediction horizon length is selected to be 3 s, the control horizon length is selected to be 0.3 s, the weight matrices are Q = diag(0.75, 1), and R = 1. On the one hand, the impact of vehicle parameter changes on the control performance is compared with conventional MPC controllers. On the other hand, the ACC performance is compared with the conventional PID control algorithm. To compare the difference in performance between the two controllers, the NMPC lower-layer deceleration controller was used in both simulations.

4.1. Simulation Results

4.1.1. Testing Results of Scenario A

The initial velocity of the front vehicle is 25 m/s, and the acceleration of the front vehicle changes sinusoidally: the acceleration amplitude is 0.5 m/s2 and the angular frequency is 0.2 rad/s; the initial velocity of the ego vehicle is 20 m/s; and the initial relative distance between the two vehicles is 40 m.
Mass change is a common internal disturbance for vehicle parameters. In order to verify the control performance under typical vehicle parameter changes, simulations are carried out with different sprung masses in test scenario A. The suffixes A, B, and C represent the three tests, respectively. Among them, test A is the reference working condition using rated mass; test B and test C are MPC using feedback correction and not using feedback correction, respectively; and their masses are 1.5 times the rated mass. Figure 7 shows the three test results in this scenario, respectively. Through the comparison, it can be seen intuitively that the speed tracking performance and distance tracking performance in test A are the best, while the performance in test B is better than test C under the influence of vehicle mass changes. After reaching the cycle following stage at 20 s, the statistics show that the speed error amplitudes in tests A, B, and C are 0.83 m/s, 0.95 m/s, and 1.19 m/s, and the distance errors are 0.52 m, 0.89 m, and 1.75 m, respectively. This also shows that MPC based on feedback correction has better robustness.
Figure 8 shows the motion state of the two vehicles under the action of the two controllers, respectively, in this scenario. In the acceleration stage of 0–5 s, the acceleration and braking behavior of the ego vehicle under the PID controller is more severe in the initial stage, with a maximum speed error of 1.51 m/s and oscillation. Based on the MPC controller, the vehicle speed error quickly converges, with a maximum speed error of 0.47 m/s, which is 31% of the PID controller. There is a similar phenomenon for the relative distance error. Under the action of the PID controller, there is a maximum overshoot of ca. 3 m for relative distance error at 6.9 s. After reaching the cycle following stage at 23 s, the speed error amplitude under the action of the MPC controller is calculated to be 0.56 m/s, which is 81% of that under the action of the PID controller, and it is 0.69 m/s. The relative distance error amplitude under the action of MPC controller is 0.43 m, which is 64% of that under the action of PID controller, and it is 0.67 m.

4.1.2. Testing Results of Scenario B

The initial speed of the front vehicle is 20 m/s, and the acceleration of the front vehicle changes stepwise several times. During the period of 10–20 s, the front vehicle accelerates to 35 m/s with an acceleration of 1.5 m/s2. During the period of 30–35 s, the front vehicle decelerates to 25 m/s with a deceleration of −2 m/s2. The initial speed of the ego vehicle is 20 m/s, and the initial relative distance between the two vehicles is 40 m.
Figure 9 shows the motion state of the two vehicles under the action of the two controllers in this scenario. During the constant speed stage of 0–10 s, the acceleration and braking amplitudes of the ego vehicle are greater under the PID controller, and the MPC controller is more stable. After that, when the front vehicle acceleration changes four times, the PID controller has a larger overshoot compared to the MPC controller, which will affect driving comfort. Taking the acceleration stage at 10–20 s as an example, the acceleration overshoot under the MPC controller is 0.05 m/s2, which is 27.8% of that under the PID controller, which is 0.18 m/s2. In addition, during the constant speed stage of 20–30 s, the MPC controller converges the speed error and relative distance error to the allowable range at 21.9 s, while the PID controller fails to control the distance error in a timely manner after converging the speed error to the allowable range at 21.7 s. Therefore, the MPC controller can track the desired distance and desired speed faster at the same time. The same effect is achieved during the constant speed stage of 35–50 s.

4.2. Experiments Results

To verify the performance of the proposed ACC control algorithm, a test vehicle was modified for real vehicle testing. As shown in Figure 10, the test vehicle and the front vehicle are in the test field. The test road surface is asphalt pavement after rain, and its road adhesion coefficient has a range of uncertainties. The test vehicle is equipped with a millimeter-wave radar and a front-facing camera to obtain the relative motion status of the front vehicle. The torque interface of the EMS system is open, and the desired torque can be obtained through the controller area network (CAN) to control the engine torque. The ego vehicle is equipped with a BBW system based on the ESC system.
The road test includes two parts, one is to test the performance difference between the NMPC controller and the PID controller in vehicle deceleration control, the other part is to test the performance difference between the proposed MPC controller and the traditional PID controller in ACC control. Some key parameters of the sensors are shown in Table 1.

4.2.1. Experiments results of Deceleration Controller

Figure 11 shows the step response of the NMPC deceleration controller and the PID deceleration controller. The overshoot of the NMPC deceleration controller is 0.21 m/s2, which is smaller than that of the PID controller at 0.61 m/s2. At the same time, the steady-state error of the deceleration under the NMPC controller approaches zero, while the deceleration under the PID controller has a certain degree of vibration. Figure 12 shows the ramp response of the NMPC deceleration controller and PID deceleration controller. The NMPC deceleration controller has a more stable deceleration change and a smaller overshoot than the PID deceleration controller.

4.2.2. Experiments Results of ACC Strategies

The ACC test scenario is shown in Figure 10. The initial speed of the ego vehicle and the front vehicle is 10 m/s, and the initial relative distance between the two vehicles is about 25 m. The speed of the front vehicle is shown in Figure 13, which includes an acceleration process and a deceleration process. The allowable range of velocity error is ±0.5 m/s, and the allowable range of distance error is ±0.5 m. In order to ensure the consistency of the motion state of the front vehicle during multiple tests, after recording the motion data of the front vehicle during the first test, the virtual front vehicle is used in subsequent tests, and the processed relative motion state data are directly input into the ACC controller.
Figure 13 and Figure 14, respectively, show the performance of the ACC system based on the MPC controller and the PID controller in this test scenario. Under the PID controller, the acceleration and braking amplitude of the ego vehicle in the initial stage is larger, its initial acceleration exceeds 0.5 m/s2, and the MPC controller is more stable. During the acceleration and deceleration process of the front vehicle, both the MPC controller and the PID controller can effectively track the velocity of the front vehicle after 23 s and converge the tracking error within the allowable range. However, at the same time, the MPC controller can track the target distance better and control the error within the allowable range after 26 s, while the PID controller has a large tracking error and cannot control the error to the allowable range in time. In addition, the designed NMPC deceleration controller can accurately track the desired deceleration, which provides a guarantee for the performance of the ACC system.

5. Conclusions

This paper proposes a hierarchical ACC system framework based on the BBW system. On the one hand, the upper-layer controller is designed based on the MPC algorithm to realize the multi-objective cooperative control of the desired vehicle speed and the desired relative distance. On the other hand, by analyzing the dynamic model of the vehicle and the braking system model of the HCU, an NMPC deceleration controller is proposed to achieve a stable and fast response to the deceleration.
The simulation and experimental results show that the proposed ACC control strategy can achieve coordinated control of multiple control objectives at the same time. Additionally, compared with traditional PID controllers, it can more reliably control the vehicle’s motion state when the front vehicle state suddenly changes. At the same time, compared with the traditional PID deceleration controller, the NMPC deceleration controller can also track the desired deceleration more accurately and smoothly. Therefore, the comfort and reliability of the control process can be effectively improved.
As an assisted driving system that improves comfort, the ACC system needs to consider many other optimization objectives, such as fuel economy. Future research directions will focus on improving the proposed ACC strategy, verifying the stability and robustness of the system in more test scenarios, optimizing the design parameters and control logic of the hydraulic control unit, and improving the quality of deceleration control.

Author Contributions

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

Funding

This research was funded by the National Key Research and Development Program of China, grant number 2022YFB2503102.

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 interest. The funders had no role in the design of the study; in the collection, analyses, or interpretation of data; in the writing of the manuscript; or in the decision to publish the results.

References

  1. Shakouri, P.; Ordys, A.; Askari, M.R. Adaptive cruise control with stop&go function using the state-dependent nonlinear model predictive control approach. ISA Trans. 2012, 51, 622–631. [Google Scholar] [CrossRef] [PubMed]
  2. Yang, Z.; Wang, Z.; Yan, M. An Optimization Design of Adaptive Cruise Control System Based on MPC and ADRC. Actuators 2021, 10, 110. [Google Scholar] [CrossRef]
  3. Zhang, L.; Zhang, Z.; Wang, Z.; Deng, J.; Dorrell, D.G. Chassis Coordinated Control for Full X-by-Wire Vehicles-A Review. Chin. J. Mech. Eng. 2021, 34, 42. [Google Scholar] [CrossRef]
  4. Souza, A.M.d.; Pedrosa, L.L.C.; Botega, L.C.; Villas, L. Itssafe: An Intelligent Transportation System for Improving Safety and Traffic Efficiency. In Proceedings of the 2018 IEEE 87th Vehicular Technology Conference (VTC Spring), Porto, Portugal, 3–6 June 2018; pp. 1–7. [Google Scholar]
  5. Vahidi, A.; Eskandarian, A. Research advances in intelligent collision avoidance and adaptive cruise control. IEEE Trans. Intell. Transp. Syst. 2003, 4, 143–153. [Google Scholar] [CrossRef] [Green Version]
  6. Spiliopoulou, A.; Perraki, G.; Papageorgiou, M.; Roncoli, C. Exploitation of ACC systems towards improved traffic flow efficiency on motorways. In Proceedings of the 2017 5th IEEE International Conference on Models and Technologies for Intelligent Transportation Systems (MT-ITS), Naples, Italy, 26–28 June 2017; pp. 37–43. [Google Scholar]
  7. Yu, Q.; Lei, L.; Bao, Y.; Wang, L. Research on Safety and Traffic Efficiency of Mixed Traffic Flows in the Converging Section of a Super-Freeway Ramp. Sustainability 2022, 14, 13234. [Google Scholar] [CrossRef]
  8. Zhang, J.; Ioannou, P.A. Longitudinal control of heavy trucks in mixed traffic: Environmental and fuel economy considerations. IEEE Trans. Intell. Transp. Syst. 2006, 7, 92–104. [Google Scholar] [CrossRef]
  9. Pradhan, R.; Majhi, S.K.; Pradhan, J.K.; Pati, B.B. Antlion optimizer tuned PID controller based on Bode ideal transfer function for automobile cruise control system. J. Ind. Inf. Integr. 2018, 9, 45–52. [Google Scholar] [CrossRef]
  10. Chaturvedi, S.; Kumar, N. Design and Implementation of an Optimized PID Controller for the Adaptive Cruise Control System. IETE J. Res. 2021, 1–8. [Google Scholar] [CrossRef]
  11. Sawant, J.; Chaskar, U.; Ginoya, D. Robust Control of Cooperative Adaptive Cruise Control in the Absence of Information About Preceding Vehicle Acceleration. IEEE Trans. Intell. Transp. Syst. 2021, 22, 5589–5598. [Google Scholar] [CrossRef]
  12. Li, S.E.; Deng, K.; Li, K.; Ahn, C. Terminal sliding mode control of automated car-following system without reliance on longitudinal acceleration information. Mechatronics 2015, 30, 327–337. [Google Scholar] [CrossRef]
  13. Ma, H.; Chu, L.; Guo, J.; Wang, J.; Guo, C. Cooperative Adaptive Cruise Control Strategy Optimization for Electric Vehicles Based on SA-PSO With Model Predictive Control. IEEE Access 2020, 8, 225745–225756. [Google Scholar] [CrossRef]
  14. Nie, Z.; Farzaneh, H. Adaptive Cruise Control for Eco-Driving Based on Model Predictive Control Algorithm. Appl. Sci. 2020, 10, 5271. [Google Scholar] [CrossRef]
  15. Xu, Y.; Chu, L.; Zhao, D.; Chang, C. A Novel Adaptive Cruise Control Strategy for Electric Vehicles Based on a Hierarchical Framework. Machines 2021, 9, 263. [Google Scholar] [CrossRef]
  16. Remfrey, J.; Gruber, S.; Ocvirk, N. Hydraulic brake systems for passenger vehicles. In Handbook of Driver Assistance Systems; Springer International Publishing: Cham, Switzerland, 2016; pp. 1–23. [Google Scholar] [CrossRef]
  17. Liu, H.; He, R.; Wu, J.; Sun, W.; Zhu, B. Linear Electro-Magnetic Valve Characteristic Analysis and Precise Pressure Control of the Electro-Hydraulic Brake System. In Proceedings of the SAE 2016 World Congress and Exhibition, Detroit, MI, USA, 12–14 April 2016. [Google Scholar]
  18. Jin, L.; Song, C.; Li, J. Controll algorithm of combination with logic gate and PID control for vehicle electronic stability control. In Proceedings of the 2010 2nd International Conference on Advanced Computer Control, Shenyang, China, 27–29 March 2010; pp. 345–349. [Google Scholar]
  19. Meng, A.; Wang, Z.; Song, J.; Pan, N. Critical Component Modeling and System Simulation of Hydraulic Control Unit of Automotive Electronic Stability Program. Trans. Chin. Soc. Agric. Mach. 2013, 44, 1–5. [Google Scholar] [CrossRef]
  20. Fang, J.; Wang, X.; Wu, J.; Yang, S.; Li, L.; Gao, X.; Tian, Y. Modeling and Control of a High Speed On/Off Valve Actuator. Int. J. Automot. Technol. 2019, 20, 1221–1236. [Google Scholar] [CrossRef]
  21. Han, W.; Xiong, L.; Yu, Z. Braking pressure control in electro-hydraulic brake system based on pressure estimation with nonlinearities and uncertainties. Mech. Syst. Signal Process. 2019, 131, 703–727. [Google Scholar] [CrossRef]
  22. Zhao, X.; Li, L.; Song, J.; Li, C.; Gao, X. Linear Control of Switching Valve in Vehicle Hydraulic Control Unit Based on Sensorless Solenoid Position Estimation. IEEE Trans. Ind. Electron. 2016, 63, 4073–4085. [Google Scholar] [CrossRef]
  23. Braun, T.; Reuter, J.; Rudolph, J. Observer Design for Self-Sensing of Solenoid Actuators with Application to Soft Landing. IEEE Trans. Control Syst. Technol. 2019, 27, 1720–1727. [Google Scholar] [CrossRef]
  24. Zhao, Y.; Yang, Y. Pressure control for pneumatic electric braking system of commercial vehicle based on model predictive control. IET Intell. Transp. Syst. 2021, 15, 1522–1532. [Google Scholar] [CrossRef]
  25. Kayacan, E. Multiobjective H∞ Control for String Stability of Cooperative Adaptive Cruise Control Systems. IEEE Trans. Intell. Veh. 2017, 2, 52–61. [Google Scholar] [CrossRef]
  26. Cheng, S.; Li, L.; Mei, M.M.; Nie, Y.L.; Zhao, L. Multiple-Objective Adaptive Cruise Control System Integrated With DYC. IEEE Trans. Veh. Technol. 2019, 68, 4550–4559. [Google Scholar] [CrossRef]
  27. Sun, X.; Cai, Y.; Wang, S.; Xu, X.; Chen, L. Optimal control of intelligent vehicle longitudinal dynamics via hybrid model predictive control. Robot. Auton. Syst. 2019, 112, 190–200. [Google Scholar] [CrossRef]
  28. Meng, A.; Garris, C.; Wei, L.; Liu, H. Visual System Analysis of High Speed On-Off Valve Based on Multi-Physics Simulation; SAE Technical Paper: Warrendale, PA, USA, 2022; ISSN 0148-7191. [Google Scholar]
  29. Gao, X.; Yang, Y.; Zhao, X.; Li, C. Non-linear dynamic modelling of a switching valve driven by pulse width modulation in the hydraulic braking system of a vehicle. Proc. Inst. Mech. Eng. Part D J. Automob. Eng. 2017, 231, 1511–1529. [Google Scholar] [CrossRef]
  30. Liu, Z.; Cheng, S.; Ji, X.; Li, L.; Wei, L. A Hierarchical Anti-Disturbance Path Tracking Control Scheme for Autonomous Vehicles Under Complex Driving Conditions. IEEE Trans. Veh. Technol. 2021, 70, 11244–11254. [Google Scholar] [CrossRef]
Figure 1. Schematic diagram of vehicle cruising process.
Figure 1. Schematic diagram of vehicle cruising process.
Actuators 12 00249 g001
Figure 2. Schematic diagram one hydraulic circuit of HCU.
Figure 2. Schematic diagram one hydraulic circuit of HCU.
Actuators 12 00249 g002
Figure 3. Schematic diagram of motor and plunger pump.
Figure 3. Schematic diagram of motor and plunger pump.
Actuators 12 00249 g003
Figure 4. Schematic diagram of the isolate valve.
Figure 4. Schematic diagram of the isolate valve.
Actuators 12 00249 g004
Figure 5. Schematic diagram of the control volume of the isolate valve.
Figure 5. Schematic diagram of the control volume of the isolate valve.
Actuators 12 00249 g005
Figure 6. The overall architecture of the hierarchical ACC controller.
Figure 6. The overall architecture of the hierarchical ACC controller.
Actuators 12 00249 g006
Figure 7. Testing results of scenario A with sprung masse change.
Figure 7. Testing results of scenario A with sprung masse change.
Actuators 12 00249 g007
Figure 8. Testing results of scenario A by different controllers.
Figure 8. Testing results of scenario A by different controllers.
Actuators 12 00249 g008
Figure 9. Testing results of scenario B by different controllers.
Figure 9. Testing results of scenario B by different controllers.
Actuators 12 00249 g009
Figure 10. Test environment for ACC system.
Figure 10. Test environment for ACC system.
Actuators 12 00249 g010
Figure 11. Step response of the different deceleration controllers in experiments.
Figure 11. Step response of the different deceleration controllers in experiments.
Actuators 12 00249 g011
Figure 12. Ramp response of the different deceleration controllers in experiments.
Figure 12. Ramp response of the different deceleration controllers in experiments.
Actuators 12 00249 g012
Figure 13. Test results of the ACC system based on the MPC controller.
Figure 13. Test results of the ACC system based on the MPC controller.
Actuators 12 00249 g013
Figure 14. Test results of ACC system based on the PID controller.
Figure 14. Test results of ACC system based on the PID controller.
Actuators 12 00249 g014
Table 1. Key parameters of the sensors.
Table 1. Key parameters of the sensors.
ParametersValues
Data update frequency15–20 Hz
Relative distance accuracy±0.4 m
Relative velocity accuracy±0.1 km/h
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

Mu, H.; Li, L.; Mei, M.; Zhao, Y. A Hierarchical Control Scheme for Adaptive Cruise Control System Based on Model Predictive Control. Actuators 2023, 12, 249. https://doi.org/10.3390/act12060249

AMA Style

Mu H, Li L, Mei M, Zhao Y. A Hierarchical Control Scheme for Adaptive Cruise Control System Based on Model Predictive Control. Actuators. 2023; 12(6):249. https://doi.org/10.3390/act12060249

Chicago/Turabian Style

Mu, Hongyuan, Liang Li, Mingming Mei, and Yongtao Zhao. 2023. "A Hierarchical Control Scheme for Adaptive Cruise Control System Based on Model Predictive Control" Actuators 12, no. 6: 249. https://doi.org/10.3390/act12060249

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