Next Article in Journal
Objective and Perceived Risk in Seismic Vulnerability Assessment at an Urban Scale
Next Article in Special Issue
Application of Machine Learning Algorithms for Sustainable Business Management Based on Macro-Economic Data: Supervised Learning Techniques Approach
Previous Article in Journal
Dynamic Evolution, Spatial Differences, and Driving Factors of China’s Provincial Digital Economy
Previous Article in Special Issue
Transitioning to a Circular Economy: A Systematic Review of Its Drivers and Barriers
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Intelligent Driver Assistance and Energy Management Systems of Hybrid Electric Autonomous Vehicles

1
School of Engineering, RMIT University, Melbourne, VIC 3083, Australia
2
Division of Mechatronics, Mechanical Engineering Institute, Vietnam Maritime University, Haiphong 180000, Vietnam
*
Author to whom correspondence should be addressed.
Sustainability 2022, 14(15), 9378; https://doi.org/10.3390/su14159378
Submission received: 21 May 2022 / Revised: 21 July 2022 / Accepted: 26 July 2022 / Published: 31 July 2022
(This article belongs to the Special Issue Circular Economy and Artificial Intelligence)

Abstract

:
Automotive companies continue to develop integrated safety, sustainability, and reliability features that can help mitigate some of the most common driving risks associated with autonomous vehicles (AVs). Hybrid electric vehicles (HEVs) offer practical solutions to use control strategies to cut down fuel usage and emissions. AVs and HEVs are combined to take the advantages of each kind to solve the problem of wasting energy. This paper presents an intelligent driver assistance system, including adaptive cruise control (ACC) and an energy management system (EMS), for HEVs. Our proposed ACC determines the desired acceleration and safe distance with the lead car through a switched model predictive control (MPC) and a neuro-fuzzy (NF) system. The performance criteria of the switched MPC toggles between speed and distance control appropriately and its stability is mathematically proven. The EMS intelligently control the energy consumption based on ACC commands. The results show that the driving risk is extremely reduced by using ACC-MPC and ACC-NF, and the vehicle energy consumption by driver assistance system based on ACC-NF is improved by 2.6%.

1. Introduction

Autonomous vehicles (AV), i.e., vehicles that are derived by computers, are coming to our roads [1,2]. It is anticipated that companies will have a USD 7 trillion annual revenue stream from the AVs market in 2050 [3]. They are supposed to bring us more safety, relaxation, and sustainability than traditional vehicles. Congestions, fuel consumption, and CO2 emissions are also expected to be reduced by AVs. Adaptive cruise control (ACC) is one of the main parts of AVs, which controls the vehicle acceleration based on the driving style. Sensors, such as radar, lidar, or a camera are used to observe the road and inform ACC about the relative distance and speed to the leading vehicle. ACC keeps a desired distance from the leading vehicle by adjusting the throttle and/or the brake system automatically. In a reasonable driving condition, a vehicle equipped with ACC travels at a driver-set velocity by controlling the throttle, similar to the operation of conventional cruise control. In the case of detecting a lead vehicle, the ACC system performs calculations to determine whether the vehicle is still able to travel at a set-speed. If the measured distance between the two vehicles is less than the safe distance, the ACC sends appropriate signals to the engine or braking system to decelerate the vehicle.
The global commitment toward sustainability [4] is expected to stimulate investments in new technologies. The transportation sector is notoriously known as one of the major contributors in increasing CO2 emissions worldwide. The feasibility study of an electrified transportation system via hybrid electric vehicle (HEV) and electric vehicle for zero or low carbon emission has been studied [5]. These emission figures are directly proportional to the energy consumed by the same sector. According to the Australian Department of the Environment and Energy (2019) report, the road transport sector was responsible for 19% of overall energy consumption in Australia. Mostly from passenger and light commercial vehicles, which are solely driven by ICE.
The desire to reduce carbon emissions due to transportation sources has led over the past decade to the development of new propulsion technologies, including hybrid, plug-in hybrid, and battery electric vehicles [6]. With more stringent laws and policies to reduce CO2 emissions and mandates to decrease the dependence on fossil fuel resources, automotive manufacturers are developing new technologies and design concepts to meet the new laws and regulations. Electric vehicles have been introduced, but they still face many challenges, such as limited travel range and lack of existing charging stations infrastructure to accommodate the increase in their numbers. Thus, different implementations of hybrid vehicles have been developed as an alternative to the full induction of electric vehicles to the roads. The plug-in HEV is one of the most successful implementations of HEV. It has the suitable configuration to charge the battery when there is an available charging station, as well as adding fuel to ICE when electric charge is not charging station, as well as adding fuel to ICE when electric charge is unavailable. Moreover, the battery can also be charged during engine braking or directly from the ICE [4].
AVs can be powered in the form of hybrid electric vehicles (HEV)s, which are driven using a combination of an electric motor and the conventional internal combustion engine (ICE) [7]. An HEV has many benefits over a pure electric vehicle (EV) in terms of travelling range and convenience, as the battery onboard can be charged automatically without the need for a charging station. It can consume considerably less fuel compared to the traditional ICEs [7]. Despite these advantages, energy management problems emerge in HEVs to ensure the efficient operation of the battery [4].
HEVs are divided into three categories: series (S-HEV), parallel (P-HEV), and series/parallel (S/P-HEV). Synchronizing multiple power sources and controlling optimal power flow between mechanical and electrical parts has less complexity in P-HEVs than other types [8]. Therefore, P-HEV is considered in this paper, for which the power flow is illustrated in Figure 1 as a combination of ICE, powertrain, motor, and pack of batteries.
The automotive powertrain is a complex, a highly non-linear, and a time-varying dynamical system by nature [2]. Several algorithms have been proposed to solve the ACC problem, such as a PID controller [9], a look-ahead control system [10], a linear quadratic control optimal synthesis approach [11], a recurrent cerebellar model articulation controller [12], and a model predictive control [13,14,15]. Augmenting the EM to the vehicle’s powertrain makes it even more sophisticated to control. Intelligent and learning-based algorithms show capabilities to deal with these complexities [16,17,18,19,20,21]. Although not straightforward, fuzzy control can translate the experiences and knowledge of expert drivers to if-then rules. A tuning process is required to obtain the optimal parameters and membership functions for the fuzzy system. This process can be managed using a neuro-fuzzy inference system. By embedding a neural network into the traditional fuzzy control system, the membership functions and if-then rules can be optimized using the training dataset. The biggest challenges for autonomous vehicles are: (i) make decisions faster in very diverse conditions, (ii) important potential in reducing pollution by optimizing their routes, (iii) considerable gap between the self-drive technology level and the current regulations, (iv) safety and imminent accidents, and (v) cyber security to defend against attacks [22,23].
This paper proposes an intelligent driver assistance system that includes a neuro-fuzzy (NF)-based EMS combined with a switched MPC system for ACC. The controller is designed to maintain a safe distance between two successive cars while the energy consumption for the following vehicle, which is a P-HEV, is reduced. The ACC controller switches between a speed and distance control mode based on the vehicle condition. This problem falls in the switched MPC category, which has been widely studied in the control community [24,25]. Asymptotic stability of the propose switched MPC is proven mathematically. The controller’s performance is investigated under combined load scenarios, including driver behaviour, environment conditions, and vehicle specifications. The proposed controller is also compared with a model predictive controller (MPC)-based ACC in safety and energy saving. It is shown that the proposed controller can better manage nonlinearities in the energy saving of a P-HEV, resulting in less fuel consumption.
The rest of the paper is formatted as follows: Section 2 presents the problem formulation, Section 3 introduces the vehicle configuration and road power demand of the ego car, Section 4 presents the proposed driver assistance system for the ego car, followed by Section 5 illustrating the simulation results and discussion. Section 6 shows the conclusions.

2. Problem Formulation

Figure 2 illustrates the scenario considered in this paper where an ego HEV follows a lead vehicle in the same lane. x l ,   v l ,   and   a l symbolize the position, velocity, and acceleration of the lead car, respectively. Those of the ego car are represented as xe, ve, and ae, respectively. The ego P-HEV is equipped with an ACC and appropriate sensors to measure the relative distance d = x l x e and relative velocity v = v l v e . Figure 4 depicts the designed driver assistance system for the ego car, including an ACC and an EMS. The spacing error Δ d , and the relative speed v are defined as,
Δ d = d d s a f e
v = v l v e
The control objectives are considered as follows:
  • The ACC is aimed to maintain a safe car following distance while the ego car follows the speed of the lead car. That means Δ d = ϵ > 0 for a small ϵ and v 0 ;
  • The EMS should reduce the energy consumption of the ego car.
Generally, an ACC controller is proposed to be hierarchical, including an upper-level controller and a lower-level controller [26]. The upper-level controller typically regulates the desired acceleration for the vehicle based on the relative speed and relative distance measured to the lead car in the same lane (as shown in the ACC block in Figure 4). The lower-level controller regulates the throttle and brake to follow the acceleration/deceleration from the upper-level controller. In this paper, the upper-level controller is emphasized, so the lower-level controller is assumed to be well-designed.

3. Vehicle Configuration and Road Power Demand

Before starting the controller design process, the modelling of different parts of the P-HEV is reviewed here.

3.1. Internal Combustion Engine

Figure 3 depicts a typical internal combustion engine. Considering the air mass entering the manifold (mi), the manifold pressure (Pm), and the engine speed (ωe) as the states and the throttle angle (α) as the input signal, the following nonlinear state-space equations describe the dynamics of ICE [27]:
x ˙ 1 ( t ) = M A X · [ 1 e 9 ( x 2 ( t ) P a t m 1 ) ] [ 1 cos ( 1.14459 u ( t ) 1.06 ) ] x ˙ 2 ( t ) = V e η v o l 4 π V m x 2 ( t ) x 3 ( t ) + M A X . R . T V m · [ 1 e 9 ( x 2 ( t ) P a t m 1 ) ] [ 1 cos ( 1.14459 u ( t ) 1.06 ) ] x ˙ 3 ( t ) = C T V e η v o l 4 π I e R T · A F I ( t λ ) · S P I ( t δ ) · x 2
in which x(t) = [x1, x2, x3] = [mi, Pm, ωe] is the state vector, u(t) = α(t) is the engine input signal, and 0 ≤ α ≤ 79.46°. The following parameters are considered for the engine [27]: MAX = 0.1843 Kg/s, Ve = 0.0038 m3, Vm = 0.0027 m3, AFI = SPI = 1 and λ = δ = 0, i.e., no delay is considered. Despite these simplifications, Equation (3) is still a sophisticated nonlinear system to control. The mass fuel rate consumption can be represented as static functions of engine torque τ e and the speed of engine ω e .
m ˙ f u e l = ω e · τ e q c · η m · η e
where q c is the combustion energy, η m = 0.9 [28] is the mechanical efficiency, and η e is the engine efficiency.

3.2. Electric Motor

An electric motor generates extra torque on the crankshaft when required. It can also work in the generation mode to generate electricity from the crankshaft rotation and charge the battery. The torque generated by the EM can be calculated as,
τ m = α e τ e m a x
where α e and τ e m a x are throttle electronic signal and the max motor torque, respectively. The supplied battery power Pb is calculated as follows [29].
P b = τ m · ω m 9550   η m
where η m is the efficiency of the motor, τ m is the output torque of the motor, ω m is the motor speed, and P b (kW) is the power of the battery pack.

3.3. Battery

The battery in P-HEV acts as both an energy storage and a source of power. The battery charge capacity Q illustrates the maximum power stored that can be stored in the battery. A battery’s state-of-charge (SoC) is defined as the ratio of the remaining charge over its full capacity; thus, 0 ≤ SoC ≤ 1 where SoC = 1 means the battery is fully charged. Battery discharge results in the SoC varying with the rate,
d ( S o C ) d t = U 0 U 0 2 4 P b R 2 Q R
where U 0 is open circuit voltage, R is battery internal resistance, Q is battery charge capacity. Pb can be negative (battery absorbs power from the ICE) and positive (battery provides power to drive the powertrain). To obtain the best performance and prolong the lifecycle of a battery, the SoC is typically limited to an interval, which can be described as follows.
S o C m i n S o C ( t ) S o C m a x

3.4. Road Power Demand

The total required power of a vehicle is determined as [8],
P R P D = P r f + P d g + P s l o p e + P a c c + P d = C r o l l i n g m g cos θ · v t + C d r a g ( φ ) · 1 2 φ ( v w + v t ) 2 A ( φ ) · v t + m g sin θ · v t + M C r o o m d T r o o m d t + m v t d v t d t .  
where m is the vehicle mass, θ depicts road slope, M presents the air mass inside the cabin, Troom is the air temperature in the cabin, A ( φ ) is front surface area, v w is the absolute wind velocity, v t is the speed of the vehicle, C r o l l i n g is the road friction coefficient, C d r a g is the drag coefficient, and ρ is the air density. All the parameters exploited to estimate the road power demand are shown in Table 1.
Driver behavior (the vehicle’s speed) is obtained from the ACC system. Road and wind profiles are environmental conditions considered in this paper. The road data with characteristics mimicking the real roads is created by using the method presented in [30]. The Poisson distribution is utilized to develop the amount of road segments. The lengths of each road segment are obtained by using the exponential distribution. The Rayleigh distribution is employed to model the road’s height up and down hills. The left and the right bends of the road are supposed to have a Gaussian distribution. A wind profile is also obtained from the model in [30]. It is a collection of sections of different lengths, wind speeds, and directions. The range, wind speed, and direction are modelled by using the exponential, Weibull, and uniform distribution models, respectively. The road power demand should be supplied by both ICE and EM [31]. It means,
P R P D = P I C E ( t ) + P b ( t )
Therefore, the fuel consumption rate of Equation (4) is updated to [29],
m ˙ e q v = m ˙ f u e l + s ( t ) · P b H L H V
where Pm is the battery power (kW) and HLHV is the fuel lower heating value (kJ/kg). s(t) is an equivalent factor defined as [29],
s ( t ) = λ ( t ) H L H V Q U 0
where λ ( t ) is the co-state value that can be considered as an equivalent weight factor between fuel consumption and electrical power consumption. The optimal value of this factor is obtained from an iterative algorithm to fascinate the boundary of the SoC, and more details can be found in [32].

4. Proposed Intelligent Power Driver Assistance System for the Ego Car

Figure 4 depicts the designed driver assistance system for the ego car, including two parts: the ACC and the EMS. The control system is designed to ensure that the ego car maintains a safe distance from the lead car and increases its fuel economy.

4.1. Adaptive Cruise Control

4.1.1. Adaptive Cruise Control Based on Switched MPC

The ACC vehicle model can be defined as follows [13].
τ d a e ( t ) d t + a e ( t ) = u ( t )
where τ refers to the time lag depending on the finite bandwidth of the lower-level controller and u depicts the acceleration command calculated from the upper-level control. By defining the state vector z ( t ) = [ Δ d ( t ) , Δ v ( t ) , a e ( t ) ] T , the state-space model of the equation of motion becomes
z ˙ ( t ) = [ 0 1 0 0 0 1 0 0 1 τ ] z ( t ) + [ 0 0 1 τ ] u ( t )
MPC is a feedback control algorithm that uses the model plant to predict the future outputs of a process. It also uses the optimizer, which guarantees that the predicted plant output tracks the desired reference. By solving an optimization problem, the MPC controller tries to minimize the error between the reference and the predicted output over a future horizon, possibly subject to constraints on the manipulated inputs and outputs [33].
The control objective for the ego car is to maintain its speed close to the lead car while the relative distance is safe, i.e., Δ d 0   and v ( k ) 0 as k reaches to infinity. A switched model predictive control (SAMPC) is used to achieve this objective. Acceleration of the ego vehicle should be adaptively changed in order to regulate Δ d . The acceleration command is calculated by solving the following constrained optimization problem during each sampling period [33].
Min J ( t ) u = t t + T { z T ( t + k ) Q z ( t + k ) + Δ u T ( t + k ) R Δ u ( t + k ) } d k s . t { Δ d 0 v m i n v e ( k ) v m a x a m i n a e ( k ) a m a x u m i n u ( k ) u m a x .  
where t is the current time, p is the prediction horizon, and Δ u is the increment of the control input. Q t ,   R t Δ u , and R t u refer to the weight matrices for the following error, change rate, and magnitude of the control input, respectively.
As a normal ACC, the MPC control objective should be distance control, i.e., z = z 1 = Δ d in Equation (15). However, we will show in simulations that the performance of such a controller is poor when the ego car falls behind for any reason. In order to solve this issue, an AMPC is considered in which the control objective is adaptively changed based on the distance Δ d between ego and lead cars. When Δ d is large, i.e., the ego vehicle is far behind the lead one, AMPC switches to a speed control system. Therefore, z = z 2 = Δ v in the optimization problem (15), which results in accelerating the ego car to fill its gap with the lead. However, when Δ d becomes reasonably close to d d e f a u l t , the control system switches to distance control and z = z 1 = Δ d . In this case, the ego car follows the driving profile of the lead by increasing and decreasing longitudinal acceleration such that Δ d 0 .
This adaptive behavior makes the control algorithm robust against undesired disturbances. For example, if the ego car fails in tracking Δ d 0 for any reason, such as a sudden action of the lead driver or the loss of sensor signals, it will be easily compensated by switching to the speed control mode for a while.
The performance of the ACC based on MPC will be discussed in Section 5.

4.1.2. Stability of the Proposed Controller

Several research activities in switching MPC (SMPC) have been addressed by allowing switching between controllers, e.g., [34]. However, in many cases, such as the one we have in this paper, switching between different performance criteria in different operating conditions may be required. In both cases, the stability of the switching system should be studied.
Suppose that an MPC controller should be designed for the dynamical system
x ˙ = f ( x , u ) ; x ( 0 ) = x 0
with a Lipschitz function f such that the performance criteria
J p ( x , u ) = t k t k + T L p ( x ( τ ) , u ( τ ) ) d τ + F p ( x ( t k + T ) )
is optimized in which Lp is a continuous positive definite function, Fp is a continuously differentiable positive definite terminal function, and p { 1 , 2 , , P } shows which cost function is now active. The following theorem is helpful in this study [34].
Definition 1.
The average dwell time τa is the average number of time units between two consecutive switches.
Theorem 1
([35]). Assume that there exist constants μ 1 and λ 0 such that for all p’s we have
V p i ( x ) μ V p j ( x )
and
V pi ( x ( t 2 ) ) V p i ( x ( t 1 ) ) λ t 1 t 2 V p i ( x ( t ) ) d t
Then, the closed loop MPC control system with the switching performance criteria is asymptotically stable if
τ a > l n μ λ
Lemma 1.
The state space equations control system (14) controlled by the switching MPC controller (15) is asymptotically stable.
Proof.
The performance criteria of Equation (15) switch between J1 and J2, corresponding to z = z 1 = Δ d and z = z 2 = Δ v , respectively. We have,
V 1 ( z ) = z 1 T ( t + k ) Q z 1 ( t + k ) + Δ u T ( t + k ) R Δ u ( t + k )
V 2 ( z ) = z 2 T ( t + k ) Q z 2 ( t + k ) + Δ u T ( t + k ) R Δ u ( t + k )
The inequality (18) is satisfied for μ = 1 because
z 1 T ( t + k ) Q z 1 ( t + k ) z 2 T ( t + k ) Q z 2 ( t + k )
Δ d T ( t + k ) Q Δ d ( t + k ) Δ v T ( t + k ) Q Δ v ( t + k )
0 [ Δ v T ( t + k ) Δ d T ( t + k ) ] Q [ Δ v ( t + k ) Δ d ( t + k ) ]
which is satisfied due to the positive definite matrix Q. This shows that condition (18) is satisfied in our problem for μ = 1 , which indeed results in τ a > 0 from Equation (20). From Theorem 1, one can conclude that the asymptotic stability of the system is satisfied for any dwell time [35]. □

4.1.3. Adaptive Cruise Control Based on NF

The NF system exploited in this paper is the adaptive-network-based fuzzy inference system (ANFIS) proposed in [16]. Due to the inherent complexity, nonlinearity, and uncertainty under multi-scale responses, energy management control of hybrid electric autonomous vehicles is required to use intelligent control such as a fuzzy logic system or a neural network. As ANFIS is the combination of a neural network and fuzzy logic, and it gives accuracy to non-linear systems’ adaptation capability and rapid learning capacity, it is widely being used [36]. ANFIS control has been used in a wide range of engineering applications such as electrical engineering, mechanical engineering, chemical, robotics engineering, and many other engineering disciplines. It combines the artificial neural network with fuzzy logic control. This combination allows overcoming the limitation of employing fuzzy logic control as a stand-alone control technique. The fuzzy inference System (FIS) has the limitation that it is not an expert by itself. The reliability of FIS is highly dependent on the rules generated by the designer. These rules vary significantly based on the designers’ expertise in the system. If an expert assigns the wrong rules, the FIS would probably perform poorly.
Moreover, in many FIS implementations, trial and error are used to improve the rules by the designer. Hence, in order to overcome these constraints using FIS alone, an artificial neural network can be used to make the FIS expert by itself. The artificial neural network ANN uses the input–output data to learn about the system behavior, apply the correct rules, and assign the correct membership function values to obtain the best performance. ANFIS can learn and tune parameters in a fuzzy inference system by utilizing a hybrid learning algorithm. Fuzzy rules are extracted at each layer of a neural network. The Tankagi–Sugeno model is applied for the composition of if-then rules. ANFIS is composed of the five following layers, as depicted in Figure 5.
Layer 1 [37]: The action of each node j in this layer is adaptable with a node function as follows.
O 1 , j = { μ A j ( u ) , j = 1 , 2 μ B j ( v ) , j = 3 , 4
where u (or v) is the input to node j, and Aj (or Bj) is the linguistic variable related to the node membership function. μ A j ( u ) , the membership function of Aj, is represented as follows.
μ A j ( u ) = 1 1 + [ ( ( u c j ) / a j 2 ) ] b j
where u is the input and (aj, bj, cj) is the premise set.
Layer 2 [37]: Nodes in this layer perform a fixed function to calculate the product of all incoming signals.
O 2 , j = ω j = μ A j ( u ) . μ B j ( v ) , j = 1 , 2
The output signal ω j illustrates the firing strength of a rule.
Layer 3: Nodes in this layer are also static (not adaptive). They are used to determine the proportion of the j-th rule’s firing strength to the accumulation of firing strengths of all the rules. It means,
O 3 , j = ω - j = ω 1 ω 1 + ω 2 , j = 1 , 2
Layer 4: Nodes in this layer perform the following adaptive function.
O 4 = ω - j f j = ω - j ( p j x + q j y + r j ) , j = 1 , 2
where ω - j is the output of layer 3 and (pj, qj, rj) is the sequential parameter set.
Layer 5 integrates all incoming signals to produce the overall output.
O 5 , j = ω - f j = j ω j f j j ω j
To work as an ACC in a P-HEV, we design an NF system that has two input signals: the relative distance and the relative velocity between two cars. It has an output, the acceleration signal applied to the ego car. Three membership functions are constructed for all input/output signals. Several experiments are performed to obtain the training dataset, which includes these signals. The training dataset is utilized for training the model by matching the expected output with the inputs, i.e., performing supervised learning. To anticipate the feedback for the model examinations after training, a validation stage is applied, followed by testing the method on a test dataset to produce an unbiased evaluation of the performance of the eventual model. At present, there is no specific solution to divide the data for these assignments [38]. However, based on [39], the set of the data is randomly divided into training (70%), validation (20%), and testing (10%). The performance results of the training, validation, and testing process are depicted in Figure 6. The FIS is generated using the grid partition method and the hybrid learning algorithm described in [37]. The model structure and the control surface are demonstrated in Figure 7 and Figure 8. The membership functions of inputs that are automatically produced by the NF system are shown in Figure 9 and Figure 10. The performance of the ACC based on MPC will be discussed in Section 5.

4.2. Energy Management System

The EMS is proposed to determine the power-split between the ICE and the electric motor based on the total required power of the vehicle. In the vehicle, the total essential power depicts a vehicle’s fuel usage and determines how energy is exploited as the vehicle moves on the road. As shown in Figure 4, all the information about DEV (driver behaviour, environment conditions, and vehicle specification) is passed into ECU (energy calculation unit) to obtain the necessary power. It can be calculated based on Equation (9). Then, a TCU block (torque calculation unit) converts the information from the driver to the requirement for the torque, calculated as the following equation [8,40].
τ v e h i c l e = ω h r · P R P D d r · g r ( t ) · v ( t )
Simultaneously, the fuzzy logic system (FLS) block produces the optimal torque to the ICE based on the total required power of the vehicle, as shown in [40]. The operation on this FLS block is as follows. The total necessary power is classified in five groups: VL, L, N, H, and VH. Fuzzy rules are proposed so the vehicle’s engine can yield the torque close to the optimal torque area to escalate the engine performance. The output of the FLS defuzzifies the signal in three clusters: L, O, and H. By conducting many experiments, the fuzzification and defuzzification sections have been designed as Figure 11a,b, respectively.
Using the generated membership functions above, the rule-based system has been generated experimentally. Table 2 shows the FLS rules that yield the optimal engine torque to ensure that the engine state is altered to perform at the maximum achievable efficiency.
Next, a fuzzy logic controller (FLC) is used to regulate the motor throttle electronic signal. Therefore, ICE will work at its optimal operating point. The rest of the required torque, which is called auxiliary torque in this paper, will be contributed by the motor. The throttle electronic signal is the output of the FLC block, which has two inputs (the error torque and the battery SoC), i.e., the fuzzy logic controller receives the error torque and the battery SoC and governs signal α to modify the motor torque.
The torque of the motor after the FLC block can be achieved by using Equation (5). Afterward, the torque of the engine can be estimated as follows.
τ I C E = τ v e h i c l e τ m
The signal τm belongs to one of the following groups: RT, T, TU, SU, C, or RC. We also consider three groups TBT, TB, and TBC for the state of charge (SOoC) of the battery. Fuzzy rules are designed so that the appropriate throttle electronic signal is generated to provide a suitable τm. Thus, the engine is able to be operated in the optimal area but still guarantees not affecting the battery features. The output (throttle electronic signal) is divided into six clusters: RT, T, TO, SU, C, and RC. Figure 12 and Figure 13 show the membership functions of inputs of the FLC, respectively.
Figure 14 represents the membership function of the FLC’s output (throttle electronic signal). Table 3 describes the rules of the fuzzy logic controller.

5. Simulation Results and Discussion

5.1. Simulation

Simulation 1: The simulation scenario assumes the lead car follows the Highway Fuel Economy Test Cycle (HWFET). The ego car equipped with ACC based on MPC travels with an initial velocity of 10 m/s. The relative distance between the two cars at the beginning is 100 m. In the simulation, the sampling time of the controller is 0.1 s. The headway time is constant and chosen as 1.4 s. The prediction horizon p = 30. MATLAB, Simulink, and Model Predictive Control toolbox [32,41] are used in the simulation. The speed of the ego car obtained from this simulation is shown in Figure 15 and is used as input to the EMS of the ego car.
Simulation 2: The simulation conditions for simulation 2 remain the same as simulation 1, but this time the ego car is equipped with ACC based on NF.

5.2. Discussion

Both ACC based on SMPC and neuro-fuzzy can guarantee safety for the ego car. The simulation results in Figure 16 show that safety is satisfied in two cases; spacing errors are always bigger than or equal to zero, so the collision is avoided.
The ego car behaviour is satisfied as to the tracking ability of velocity working well in both cases, and the relative distance is finally adjusted to the safe values. The ego car in both cases decelerates at the beginning, to avoid a collision with the lead car, and then regulates the velocity to adapt to the lead car’s speed variation, while maintaining a safe distance computed by a constant time headway policy. The relative speed between these two vehicles is presented in Figure 15.
In terms of engine efficiency and the SoC of the battery, by applying the EMS hinged on FLC, the motor torque and the engine torque of the ego car are produced, as shown in Figure 17 and Figure 18, respectively. To date, there is no available commercial automotive computer simulator to simulate the algorithm; however, authors are working on the development of experimental analysis based on model/prototype and dimensional similitude to show the concept as well as compare with a previous published model in [42]. It is expected that the method, results, and comparison are to be published in a follow up paper. Based on the engine efficiency map, the engine is operating in a region of sub-optimal fuel efficiency in the real time conditions. For this case, the average fuel efficiency is 28.70%, the torque is regulated mainly within a range of 10–84 (Nm), and the SoC of the battery during the whole trip is 0.7192, leading to the total fuel consumption of the vehicle being 6.74 L/100 km for the duration of a 16.5 km drive [42]. In simulation 1, with the amount of torque taken from the electric motor, the engine torque of the ego car is regulated within an interval of 32–80 (Nm). Consequently, the average energy efficiency of the engine is 31.52%, and the SoC at the end of the trip is 0.7236. Therefore, in terms of the total equivalent fuel consumption, the vehicle consumed 6.14 L/100 km for a distance of 16.5 km. Meanwhile, in simulation 2, the engine of the ego car falls in the same range of 32–80 (Nm). However, mainly during the trip, the torque of the engine is closer to the optimal torque area (as shown in Figure 18), making the total equivalent fuel consumption of the car being 5.98 L/ 100 km with an average fuel efficiency of 31.58% and the SoC at the end of the trip of 0.7286. Figure 19 and Figure 20 represent the engine efficiency and SoC of the battery, respectively.

6. Conclusions

In this paper, an intelligent driver assistance system for a HEAV is proposed to do two tasks: keeping the vehicle at a safe distance from the lead vehicle and reducing energy consumption. The system combined an ACC and EMS, in which the ACC is designed by combining a switched MPC technique with an NF approach. The performances of the proposed ACC systems are simulated and evaluated by considering the primary factors that affect vehicle performance, including vehicle specification, environment conditions, and driver behaviour. This paper shows that the driver assistance system can be improved by using the ACC-NF controller compared with using the ACC-SMPC controller. The system based on SMPC can generate excellent results. Still, the MPC needs to solve the optimization problem considering future prediction in every sampling, so it causes the burden calculation load. The NF method provides a practical alternative to conventional analytical control approaches in solving nonlinear autonomous control problems to obtain a robust, less computationally expensive, and more human-like speed control simultaneously. The simulation results demonstrate that the safe distance between two successive vehicles on the same are maintained during the trip. However, with the developed driver assistance system based on the ACC-NF method, the efficiency of the engine increases, and the SoC of the battery at the end of the trip is higher, leading to the equivalent fuel consumption of the vehicle improved by 2.61% compared with the system-based ACC-SMPC method and 8.9% compared with the system without any intelligent controller.

Author Contributions

Conceptualization, D.P.V. and H.K.; Data curation, Z.A.-S. and D.B.P.; Formal analysis, D.P.V.; Investigation, Z.A.-S. and D.P.V.; Methodology, D.P.V., A.M.A., S.S.S., D.B.P. and H.K.; Writing—original draft, Z.A.-S., D.P.V. and R.J.; Writing—review & editing, A.M.A., M.F. and H.K. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Acknowledgments

The authors would like to thank Mahdi Jalili, for his helpful comments during this work.

Conflicts of Interest

The authors declare no conflict of interest.

Nomenclature

τ e Engine torque (N·m)
ω e Engine speed (rpm, rad/s)
τ m Motor torque (N·m)
ω m Motor speed (rpm·rad/s)
τ v e h i c l e Torque of vehicle (N·m)
θ Road inclination
ρ Air density, (kg/m3)
η m   Mechanical efficiency
η e   Engine efficiency
m ˙ f u e l Mass flow rate fuel consumption, kg/s
m ˙ e q v Equivalent fuel mass flow rate, kg/s
Q ˙ Power
q c Combustion energy (kJ/kg)
C d r a g Drag coefficient
C r o l l i n g Road friction coefficient
C T Constant torque
A ( ϕ ) Front surface area, m2
A F I ( λ ) Function of air to fuel ratio
A / F Air to fuel ratio
P m a Manifold pressure
P b Battery power (kW)
TIntake temperature, ° C
T r o o m Temperature of the air in the cabin, ° C
v t Speed of the vehicle at t (m/s)
v w Absolute wind speed (m/s)
V m Manifold volume, m3
V d i s p Volumetric displacement of the engine, m3
SoCState of Charge
MAXMaximum flow through the throttle
HEVHybrid Electric Vehicle
MPCModel Predictive Control
ACCAdaptive Cruise Control
SMPCSwitching MPC
AMPCAdaptive MPC
NFNeuro Fuzzy
ANFISAdaptive-Network-based Fuzzy Inference System

References

  1. Jazar, R.N.; Dai, L. Nonlinear Approaches in Engineering Applications: Automotive Applications of Engineering Problems; Springer: Berlin/Heidelberg, Germany, 2019. [Google Scholar]
  2. Marzbani, H.; Khayyam, H.; To, C.N.; Quoc, Đ.V.; Jazar, R.N. Autonomous Vehicles: Autodriver Algorithm and Vehicle Dynamics. IEEE Trans. Veh. Technol. 2019, 68, 3201–3211. [Google Scholar] [CrossRef]
  3. Lanctot, R. Accelerating the Future: The Economic Impact of the Emerging Passenger Economy; Strategy Analytics: Needham, MA, USA, 2017; Volume 5. [Google Scholar]
  4. Zöldy, M.; Zsombók, I.J.M.W.C. Modelling fuel consumption and refuelling of autonomous vehicles. MATEC Web Conf. 2018, 235, 37. [Google Scholar] [CrossRef]
  5. Khayyam, H. Automation, Control and Energy Efficiency in Complex Systems; MDPI Books: Basel, Switzerland, 2020. [Google Scholar]
  6. Marano, V.; Rizzoni, G.; Tulpule, P.; Gong, Q.; Khayyam, H. Intelligent energy management for plug-in hybrid electric vehicles: The role of ITS infrastructure in vehicle electrification. Oil Gas Sci. Technol. 2012, 67, 575–587. [Google Scholar] [CrossRef] [Green Version]
  7. Ehsani, M.; Gao, Y.; Longo, S.; Ebrahimi, K. Modern Electric, Hybrid Electric, and Fuel Cell Vehicles; CRC Press: Boca Raton, FL, USA, 2018. [Google Scholar]
  8. Khayyam, H.; Kouzani, A.; Nahavandi, S.; Marano, V.; Rizzoni, G. Intelligent energy management in hybrid electric vehicles. In Energy Management; Pérez, F.M., Ed.; IntechOpen: Vienna, Austria, 2010; pp. 147–175. [Google Scholar]
  9. Milanés, V.; Villagrá, J.; Godoy, J.; González, C. Comparing fuzzy and intelligent PI controllers in stop-and-go manoeuvres. IEEE Trans. Control Syst. Technol. 2011, 20, 770–778. [Google Scholar] [CrossRef] [Green Version]
  10. Khayyam, H.; Nahavandi, S.; Davis, S. Adaptive cruise control look-ahead system for energy management of vehicles. Expert Syst. Appl. 2012, 39, 3874–3885. [Google Scholar] [CrossRef]
  11. Liang, Z.; Ren, Z.; Shao, X. Decoupling trajectory tracking for gliding reentry vehicles. IEEE/CAA J. Autom. Sin. 2015, 2, 115–120. [Google Scholar]
  12. Lin, C.-M.; Chen, C.-H. Car-following control using recurrent cerebellar model articulation controller. IEEE Trans. Veh. Technol. 2007, 56, 3660–3673. [Google Scholar] [CrossRef]
  13. Bageshwar, V.L.; Garrard, W.L.; Rajamani, R. Model predictive control of transitional maneuvers for adaptive cruise control vehicles. IEEE Trans. Veh. Technol. 2004, 53, 1573–1585. [Google Scholar] [CrossRef]
  14. Magdici, S.; Althoff, M. Adaptive cruise control with safety guarantees for autonomous vehicles. IFAC-Pap. 2017, 50, 5774–5781. [Google Scholar] [CrossRef]
  15. Takahama, T.; Akasaka, D. Model Predictive Control Approach to Design Practical Adaptive Cruise Control for Traffic Jam. Int. J. Automot. Eng. 2018, 9, 99–104. [Google Scholar] [CrossRef] [Green Version]
  16. Jang, J.-S. ANFIS: Adaptive-network-based fuzzy inference system. IEEE Trans. Syst. Man Cybern. 1993, 23, 665–685. [Google Scholar] [CrossRef]
  17. Khayyam, H.; Fakhrhoseini, S.M.; Church, J.S.; Milani, A.S.; Bab-Hadiashar, A.; Jazar, R.N.; Naebe, M. Predictive modelling and optimization of carbon fiber mechanical properties through high temperature furnace. Appl. Therm. Eng. 2017, 125, 1539–1554. [Google Scholar] [CrossRef]
  18. Chen, H. Fuel injection control and simulation of efi engine based on anfis. In Proceedings of the 2008 International Conference on Intelligent Computation Technology and Automation (ICICTA), Changsha, China, 20–22 October 2008; pp. 191–194. [Google Scholar]
  19. Quek, C.; Pasquier, M.; Lim, B. A novel self-organizing fuzzy rule-based system for modelling traffic flow behaviour. Expert Syst. Appl. 2009, 36, 12167–12178. [Google Scholar] [CrossRef]
  20. Vatankhah, R.; Rahaeifard, M.; Alasty, A. Vibration control of vehicle suspension system using adaptive critic-based neurofuzzy controller. In Proceedings of the 2009 6th International Symposium on Mechatronics and its Applications, Sharjah, United Arab Emirates, 23–26 March 2009; pp. 1–6. [Google Scholar]
  21. Jinlin, X.; Weigong, Z.; Zongyang, G. Neurofuzzy velocity tracking control with reinforcement learning. In Proceedings of the 2009 9th International Conference on Electronic Measurement & Instruments, Beijing, China, 16–19 August 2009. [Google Scholar]
  22. Zoldy, M.; Csete, M.S.; Kolozsi, P.P.; Bordas, P.; Torok, A.J.C.S. Cognitive Sustainability. Cogn. Sustain. 2022, 1. [Google Scholar] [CrossRef]
  23. Barabás, I.; Todoruţ, A.; Cordoş, N.; Molea, A. Current challenges in autonomous driving. IOP Conf. Ser. Mater. Sci. Eng. 2017, 252, 012096. [Google Scholar] [CrossRef]
  24. Mueller, M.W.; Lee, S.J.; D’Andre, R. Design and Control of Drones. Annu. Rev. Control Robot. Auton. Syst. 2022, 5, 161–177. [Google Scholar] [CrossRef]
  25. Sajadi-Alamdari, S.A.; Voos, H.; Darouach, M. Ecological advanced driver assistance system for optimal energy management in electric vehicles. IEEE Intell. Transp. Syst. Mag. 2018, 12, 92–109. [Google Scholar] [CrossRef]
  26. Rajamani, R.; Zhu, C. Semi-autonomous adaptive cruise control systems. IEEE Trans. Veh. Technol. 2002, 51, 1186–1192. [Google Scholar] [CrossRef]
  27. Cho, D.; Hedrick, J.K. Automotive powertrain modeling for control. J. Dyn. Syst. Meas. Control 1989, 111, 568–576. [Google Scholar] [CrossRef]
  28. Michael, P.; Anthony, M. Engine Testing Theory and Practice; SAE International: Warrendale, PA, USA, 1999. [Google Scholar]
  29. Zhang, F.; Xi, J.; Langari, R. An adaptive equivalent consumption minimization strategy for parallel hybrid electric vehicle based on fuzzy pi. In Proceedings of the 2016 IEEE Intelligent Vehicles Symposium (IV), Gothenburg, Sweden, 19–22 June 2016; pp. 460–465. [Google Scholar]
  30. Khayyam, H. Stochastic models of road geometry and wind condition for vehicle energy management and control. IEEE Trans. Veh. Technol. 2012, 62, 61–68. [Google Scholar] [CrossRef]
  31. Moura, S.J.; Callaway, D.S.; Fathy, H.K.; Stein, J.L. Tradeoffs between battery energy capacity and stochastic optimal power management in plug-in hybrid electric vehicles. J. Power Sources 2010, 195, 2979–2988. [Google Scholar] [CrossRef]
  32. Kim, N.; Lee, D.; Zheng, C.; Shin, C.; Seo, H.; Cha, S. Realization of pmp-based control for hybrid electric vehicles in a backward-looking simulation. Int. J. Automot. Technol. 2014, 15, 625–635. [Google Scholar] [CrossRef]
  33. Zhang, P. Advanced Industrial Control Technology; William Andrew: Norwich, NY, USA, 2010. [Google Scholar]
  34. Müller, M.A.; Allgöwer, F. Improving performance in model predictive control: Switching cost functionals under average dwell-time. Automatica 2012, 48, 402–409. [Google Scholar] [CrossRef]
  35. Müller, M.A.; Martius, P.; Allgöwer, F. Model predictive control of switched nonlinear systems under average dwell-time. J. Process Control 2012, 22, 1702–1710. [Google Scholar] [CrossRef]
  36. Khayyam, H. Adaptive Intelligent Systems for Energy Management of Vehicles. Ph.D. Thesis, Deakin University, Burwood, Australia, 2010. [Google Scholar]
  37. Phan, D.; Bab-Hadiashar, A.; Hoseinnezhad, R.; N Jazar, R.; Jamali, A.; Pham, D.B.; Khayyam, H. Neuro-Fuzzy System for Energy Management of Conventional Autonomous Vehicles. Energies 2020, 13, 1745. [Google Scholar] [CrossRef] [Green Version]
  38. Kuhn, M.; Johnson, K. Feature Engineering and Selection: A Practical Approach for Predictive Models; CRC Press: Boca Raton, FL, USA, 2019. [Google Scholar]
  39. Khayyam, H.; Golkarnarenji, G.; Jazar, R.N. Limited data modelling approaches for engineering applications. In Nonlinear Approaches in Engineering Applications; Springer: Berlin/Heidelberg, Germany, 2018; pp. 345–379. [Google Scholar]
  40. Phan, D.; Bab-Hadiashar, A.; Lai, C.Y.; Crawford, B.; Hoseinnezhad, R.; Jazar, R.N.; Khayyam, H. Intelligent energy management system for conventional autonomous vehicles. Energy 2019, 191, 116476. [Google Scholar] [CrossRef]
  41. Bemporad, A.; Morari, M.; Ricker, N.L. Model Predictive Control Toolbox User’s Guide. The Mathworks, 2010. Available online: https://zdocs.pub/doc/model-predictive-control-toolbox-d1m49we9ow10 (accessed on 20 May 2022).
  42. Phan, D.; Amani, A.M.; Mola, M.; Rezaei, A.A.; Fayyazi, M.; Jalili, M.; Ba Pham, D.; Langari, R.; Khayyam, H.J.S. Cascade adaptive mpc with type 2 fuzzy system for safety and energy management in autonomous vehicles: A sustainable approach for future of transportation. Sustainability 2021, 13, 10113. [Google Scholar] [CrossRef]
Figure 1. Composition of a P-HEV.
Figure 1. Composition of a P-HEV.
Sustainability 14 09378 g001
Figure 2. Illustration of considered scenario.
Figure 2. Illustration of considered scenario.
Sustainability 14 09378 g002
Figure 3. A typical internal combustion engine.
Figure 3. A typical internal combustion engine.
Sustainability 14 09378 g003
Figure 4. An intelligent driver assistant architecture.
Figure 4. An intelligent driver assistant architecture.
Sustainability 14 09378 g004
Figure 5. NF system with Tagaki–Sugeno inference.
Figure 5. NF system with Tagaki–Sugeno inference.
Sustainability 14 09378 g005
Figure 6. (a) Training error for 100 epochs with 0.094709 error tolerance; (b) Training data, average error was 0.9455; (c) Validation data, average error was 0.18137; (d) Testing data; average error was 0.06927.
Figure 6. (a) Training error for 100 epochs with 0.094709 error tolerance; (b) Training data, average error was 0.9455; (c) Validation data, average error was 0.18137; (d) Testing data; average error was 0.06927.
Sustainability 14 09378 g006
Figure 7. Model structure.
Figure 7. Model structure.
Sustainability 14 09378 g007
Figure 8. Control surface.
Figure 8. Control surface.
Sustainability 14 09378 g008
Figure 9. Membership function of input 1.
Figure 9. Membership function of input 1.
Sustainability 14 09378 g009
Figure 10. Membership function of input 2.
Figure 10. Membership function of input 2.
Sustainability 14 09378 g010
Figure 11. Membership functions of the fuzzy logic system: (a) input (b) output.
Figure 11. Membership functions of the fuzzy logic system: (a) input (b) output.
Sustainability 14 09378 g011
Figure 12. The difference between the requirement torque of the vehicle and the optimal torque of ICE.
Figure 12. The difference between the requirement torque of the vehicle and the optimal torque of ICE.
Sustainability 14 09378 g012
Figure 13. The state of charge of the battery.
Figure 13. The state of charge of the battery.
Sustainability 14 09378 g013
Figure 14. Throttle electronic signal.
Figure 14. Throttle electronic signal.
Sustainability 14 09378 g014
Figure 15. Relative velocity of between two cars.
Figure 15. Relative velocity of between two cars.
Sustainability 14 09378 g015
Figure 16. Spacing error between two vehicles.
Figure 16. Spacing error between two vehicles.
Sustainability 14 09378 g016
Figure 17. Motor torque of ego car.
Figure 17. Motor torque of ego car.
Sustainability 14 09378 g017
Figure 18. Engine torque of ego car.
Figure 18. Engine torque of ego car.
Sustainability 14 09378 g018
Figure 19. Engine efficiency of ego car.
Figure 19. Engine efficiency of ego car.
Sustainability 14 09378 g019
Figure 20. State of charge of battery of ego car.
Figure 20. State of charge of battery of ego car.
Sustainability 14 09378 g020
Table 1. Vehicle specifications and parameters are used to calculate the vehicle’s required power.
Table 1. Vehicle specifications and parameters are used to calculate the vehicle’s required power.
SpecificationParametersValue
Road friction coefficient C r o l l i n g 0.015
Gravity acceleration g 9.81 m/s2
Vehicle velocity v t ACC command m/s
Wind velocity v w m/s
Mass (vehicle + equivalent rotating parts + passengers) m 1280 kg
Drag coefficient (constant) C d r a g 0.335
Front surface area A 1.9 × (1/cosϕ)
Air density ρ 1.225 kg/m3
Combustion energyqcombustion38017 kJ/kg
Wheel radiuswhr0.285 m
Differential ratiodr3.21:1
Electric motor/generator
Maximum current 480 A
Minimum voltage 120 V
Max power 75 kW
Battery pack
Chemistry Li-Ion
A cell nominal voltage 12 V
Nominal capacity 26.2 Ah
Pack battery power P B a t t e r y 4.4 kWh
Temperature [0 22 40] (0 °C)
Min voltage 9.5 V
Max voltage 16.5 V
Table 2. The rules of fuzzy logic system.
Table 2. The rules of fuzzy logic system.
Condition NumberIf
Total Required Power
Then τ o p t i m a l
1VLL
2LL
3NO
4HH
5VHH
Table 3. The rules of fuzzy logic controller.
Table 3. The rules of fuzzy logic controller.
Condition Number If e τ And SoCThen
α
Condition NumberIf
e τ
And SoCThen
α
1RCTBTTO10TUTBTTO
2RCTBRC11TUTBTO
3RCTBCRC12TUTBCTO
4CTBTTO13TTBTT
5CTBC14TTBT
6CTBCC15TTBCTO
7SUTBTTO16RTTBTRT
8SUTBSU17RTTBRT
9SUTBCSU18RTTBCTO
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Al-Saadi, Z.; Phan Van, D.; Moradi Amani, A.; Fayyazi, M.; Sadat Sajjadi, S.; Ba Pham, D.; Jazar, R.; Khayyam, H. Intelligent Driver Assistance and Energy Management Systems of Hybrid Electric Autonomous Vehicles. Sustainability 2022, 14, 9378. https://doi.org/10.3390/su14159378

AMA Style

Al-Saadi Z, Phan Van D, Moradi Amani A, Fayyazi M, Sadat Sajjadi S, Ba Pham D, Jazar R, Khayyam H. Intelligent Driver Assistance and Energy Management Systems of Hybrid Electric Autonomous Vehicles. Sustainability. 2022; 14(15):9378. https://doi.org/10.3390/su14159378

Chicago/Turabian Style

Al-Saadi, Ziad, Duong Phan Van, Ali Moradi Amani, Mojgan Fayyazi, Samaneh Sadat Sajjadi, Dinh Ba Pham, Reza Jazar, and Hamid Khayyam. 2022. "Intelligent Driver Assistance and Energy Management Systems of Hybrid Electric Autonomous Vehicles" Sustainability 14, no. 15: 9378. https://doi.org/10.3390/su14159378

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