1. Introduction
Driver and passenger safety has led to a great development of Advanced Driver Assistance Systems (ADASs) in new vehicle projects. ADASs are defined as vehicle-based intelligent safety systems, which could improve road safety in terms of crash avoidance, crash severity mitigation and protection, and post-crash phases. This has become possible thanks to the improvement of sensor technologies installed on the vehicle [
1], with the aim to obtain a more comprehensive description of the environment [
2]. Moreover, while ADAS allow the vehicle to be automated, communication between vehicles and the road infrastructure is needed to improve driving awareness and prevent the unknown intentions of other road users [
3]. Cooperative-Intelligent Transportation Systems (C-ITSs) aim at connecting vehicles to each other and to the road infrastructure, the so-called smart road, increasing traffic safety and efficiency [
4]. Therefore, the combination of ADASs and C-ITS results in a Connected and Automated Vehicle (CAV), which opens the way to a new era in the design of cooperative control systems considering both in-vehicle and roadside aspects. In this perspective, the work in [
3] described the state-of-the-art and future challenges and opportunities for CAVs, defining the main components of the future transportation systems and considering a holistic approach to deal with challenging tasks such as constrained optimal control problems and energy management strategies.
Concerning control aspects, a CAV requires the adoption of extended nonlinear time-varying models to simulate both the vehicle and the environment, so as to design an efficient control strategy. Moreover, the vehicle to be controlled needs to be subjected to multiple constraints, involving both actuator limits and constraints on maneuvers. Thus, because of its ability to exploit available models and satisfy constraints in control systems, the Model Predictive Control (MPC) is particularly suitable for CAVs. Concerning energy management, the Energy Management Strategy (EMS) of the powertrain deals with the issue of handling the energy flows in the Hybrid Electric Vehicles (HEVs) between the Internal Combustion Engine (ICE), Electric Motor (EM), and battery.
The contribution of this work is twofold and aims at developing an integration strategy that allows running both motion and powertrain control in real-time on a single MCU. First, the MPC strategy proposed in this work controls both the lateral and longitudinal dynamics of a vehicle, considering a simplified single-track model, and it was assumed that not only the motion references for the vehicle and constraints on the speed, but also some of the model parameters that depend on the road conditions, e.g., friction, slope and curvature, would be received from the smart road infrastructure through a C-ITS service. The controller had two outputs, the steering angle of the wheels and the torque request for the powertrain. The torque request was handled by the EMS through the ETESS proposed by the authors in previous works [
5,
6]. The ETESS aims at minimizing the HEV fuel consumption, and it requires a reduced computational effort with respect to existing strategies (i.e., ECMS) such that it can run on the same control unit of the MPC. This particular implementation was the second main contribution, since for the first time, a vehicle dynamics control algorithm and a powertrain management strategy were demonstrated to run in real time on the same embedded control unit.
The simplified vehicle model and the EMS proposed in this work allowed the embedded real-time implementation of a model-based design module (implemented in the MATLAB/Simulink environment, a typical approach of automotive applications) that connects in cascade the MPC and ETESS. A single Microcontroller Unit (MCU), considering the high-performance Arm-Cortex M7 MCU STM32H743ZI on the development board NUCLEO-H743ZI, was used. The aim of the real-time implementation was to demonstrate by Processor-In-the-Loop (PIL) testing that the computational burden of the cascade between the MPC and ETESS on the same MCU was lower than 10 ms, the typical cycle time of CAN messages for torque and steering, based on the methodology used by the authors in [
7].
The execution of both the motion and powertrain control on a single MCU would enable further developments in which the MCU would act as an Internet of Things (IoT) gateway between the vehicle and the surrounding environment. In particular, this gateway would allow the following communications:
Vehicle to Vehicle (V2V);
Vehicle to Infrastructure (V2I);
Infrastructure to Vehicle (I2V).
Thus, the presented solution allows considering a new hardware architecture in which the powertrain and motion controls are directly coupled from a CAV perspective. Furthermore, since a low number of state variables for the vehicle dynamics were used and a simplified EMS was adopted, this study aimed at demonstrating that the approach can be extended with additional control algorithms (i.e., path planning, eco-driving), still using the same MCU and the same CAN cycle time.
The remainder of the paper is organized as follows.
Section 2 is a revision of the state of the art about MPC for CAVs and about EMS.
Section 3 describes the proposed method to: (i) design a simplified but complete nonlinear single-track ego-vehicle model and its linearization in order to allow the implementation of an adaptive MPC; (ii) define the powertrain model and the ETESS strategy.
Section 4 describes: (i) the comparative assessment between ETESS and ECMS; (ii) the PIL test on the selected MCU.
Section 5 and
Section 6 discuss the results as well as the limitations of the current approach and future developments, respectively.
3. Methodology
This section first shows a complete nonlinear ego-vehicle model, which is then linearized to allow the design and implementation of an adaptive MPC control strategy. This strategy implements functionalities for autonomous driving, considering as control variables the steering angle at the wheels and wheels’ torque. The last control variable provides the power demand for the implemented EMS.The second part of this section reports the powertrain and driveline model and, finally, the ETESS implementation.
3.1. Vehicle Model
In order to design the MPC, a simplified but complete ego-vehicle nonlinear single-track model for combined longitudinal and lateral vehicle dynamics is used. Then, two errors (for lateral offset and yaw angle) are modeled to enable the development of Lane Keeping Systems (LKS). Eventually, a simple car-following model is derived to consider the relative distance and velocity from an ahead vehicle. All quantities are expressed in SI units unless otherwise explicitly stated.
This model will allow designing Adaptive Cruise Control (ACC), Lane Keeping System (LKS), and Emergency Electronic Brake (EEB) for ADAS, but it can be used for cooperative driving control strategies as well, considering the V2X (Vehicle to everything) and I2V (Infrastructure to Vehicle) communications between vehicle and Smart Road, for example, by using the C-ITS services ISA (Intelligent Speed Adaptation) or in-Vehicle SPeeD limits (VSPD) [
4].
3.1.1. Single-Track Model
The single-track model is derived from the four-wheeled model presented in [
33], according to the following three assumptions
- 1.
Only the front wheels are considered to be driving, so the overall wheels torque is the sum of the torque at front wheels during accelerations. Furthermore, is assumed as the sum of the torque at all the wheels during braking;
- 2.
The steering angles of the front wheels are equal to
and the small angle approximation is used [
34], considering that the control range on the steering angle at the wheels is [−5, 5]°; thus,
and
;
- 3.
The longitudinal slip ratio
(the subscripts
indicate the positioning of the wheel on the vehicle, i.e., front right
, front left
, rear left
and rear right
) is considered negligible and defined as follows
where
is the effective wheel radius,
is the specific wheel speed and
is the longitudinal vehicle speed [
34].
From assumption 3, it follows that
From the wheel dynamics, defined in (
3), the longitudinal tire forces
can be derived, depending on the longitudinal acceleration, considering (
2), and on wheel torque for each wheel
where
is the moment of inertia of the wheel [
33]. With the assumptions above and considering the lateral speed
and the yaw angle rate
, a simplified nonlinear single-track model is obtained, characterized by three state variables
in three equations
where m is the vehicle mass, the term
is the aerodynamic drag force, defined as
, with
being the air density (possibly provided by the Smart Road via I2V based on the altitude; in this case, it is assumed at sea level),
A is the maximum vehicle cross area,
is the drag coefficient depending on vehicle body shape and
is the wind speed (provided by the Smart Road via I2V). The term
refers to the sum of the front and rear wheels’ rolling resistance forces, defined as
, where
is the rolling resistance,
and
are the normal tire forces, at the front and at the rear of the vehicle, calculated as in [
34] and their sum is
, where
is the road slope angle (supposed to be known by Inertial Measurement Unit in vehicle and/or ADAS Maps and/or I2V). The term
is the gravity force component along the vehicle longitudinal axis, while
is the cornering stiffness of the tire,
, and
are the distances of the front and rear tire centers from the vehicle Center of Gravity (CoG), respectively. The terms
and
are defined in [
33] depending on the wheel masses, the vertical moment of inertia, and the front-axle track of the vehicle.
3.1.2. Equations of Errors with Respect to the Road
In order to implement an LKS, a dynamic model is considered. It is based on two additional state variables, expressed in terms of position and orientation errors with respect to the road reference system [
34]. Thus, as shown in
Figure 1, defining
as the lateral displacement (the distance of the CoG of the vehicle from the center line of the lane) and
as the relative yaw angle error concerning the road centerline (angle between the longitudinal velocity direction and the tangent to the center line), considering the road radius
is large so that the small angle assumptions can be made and supposing that the road curvature
is known from in-vehicle ADAS map and/or I2V communication, the desired yaw rate of the vehicle is defined as in [
34] as
The dynamics of lateral displacement, according to [
34] is
being
, where
is the yaw angle of the vehicle (
), this implies that
Defining , two additional states are added to the ego-vehicle model, which are assumed as measurable by ADAS sensors and maps.
3.1.3. Car-Following Model
If the ego-vehicle is preceded by another car, the relative distance and velocity from the ahead vehicle have to be considered. These measures are available considering radar and/or LiDAR and/or camera sensors commonly used in ADAS.
This study considers both the presence of an ahead vehicle and V2V (Vehicle to Vehicle) communication; thus, two additional states are necessary, e.g., the velocity of the vehicle located ahead
and the relative distance
of the ego-vehicle from the latter, as shown in
Figure 2. Assuming the availability of a Smart Road, this model takes into account the road slope
, the wind speed
, and the road friction
provided by C-ITS (e.g., I2V) services. In addition, since the MPC acts on the ego-vehicle only, the traction/braking force of the ahead vehicle
is assumed to be known thanks to the V2V communication, considering the longitudinal slip ratio to be negligible. Thus, the additional states to consider for the complete ego-vehicle model are defined below
where
(
is the maximum cross-area of the ahead vehicle and
its drag coefficient) and
is the ahead vehicle mass [
34]. All these parameters are assumed to be known and transmitted through V2V to the ego-vehicle. Then, the states
are added to the other state variables to define the complete ego-vehicle model, as detailed in the next section.
3.1.4. Complete Nonlinear Ego-Vehicle Model
The complete model of ego-vehicle is featured by the following states, control inputs and outputs
and the corresponding state space equations are (
4a)–(
4c), (
6), (
7), (
8a), (
8b).
3.1.5. Linearization of the Complete Ego-Vehicle Model
Aiming to allow MPC to work around a reference trajectory, the nonlinear model (
9) is linearized if the reference speed and/or road curvature change, even at each iteration if needed, in order to obtain a linear time-varying system [
35]. The reference speed
is assumed to be known via C-ITS and sensor fusion of radar and/or LiDAR and/or the camera provided by ADAS. For the same reason, road curvature and therefore
are known as well. The wheel steering reference
is given by the following relation [
34]
where
,
, considering single-track model assumptions. The torque set point
during acceleration is given by (
4a) at the equilibrium, while during braking, the brake model [
36] is adopted to get the set-point trajectory, e.g.,
where
P is the amount of pressure produced behind the brake disk, while applying the brake pedal and
is the brake torque, with
being the gain of the braking system. The parameter
is the lumped lag obtained by combining two lags relating to the dynamics of the servo valve and the hydraulic system,
is the pressure gain and
is the percentage of pressure on the brake pedal. Moreover,
is provided by a simple driver model featured by a PI control acting on the derivative of the speed reference, to model a driver’s behavior during braking, which is useful to obtain a reference.
The set-point trajectory for lateral velocity
is given by the solution
of (
4b) at the equilibrium, while the set points for
and
are both equal to zero. Eventually, the set point of
is assumed to be known via ADAS and V2V and the desired relative distance is defined as
where
is the theoretical safety distance depending on the ego-vehicle length
L and a response time
s of the ego car during braking [
7].
The state, input and output variables of the linearized system are defined as
where
,
and
are the set points for the states of the complete model;
during braking, while
otherwise is the set point for the wheel torque;
is the one for the wheel steering angle;
is the reference speed.
Thus, the linearized time-varying system, obtained from Jacobian computation, in the continuous time is
where
and
are the dynamic matrix and the input matrix (time varying from linearization process), respectively, and
is the output matrix (constant, because it selects only the four states featuring the outputs) [
37]. For MPC purposes, this model is discretized as
where
,
and
are the dynamic, input and output matrices of the discretized model [
37],
is the sampling time and
is the identity matrix of dimension
(number of states of the complete ego-vehicle model).
The sampling time is chosen equal to 10 ms (the typical cycle time of the CAN message for the torque request). The list of parameters and their values used in the ego-vehicle model is shown in
Table 1. Those values refer to a commercial small utility vehicle.
3.2. Model Predictive Control
MPC aims to optimize a quadratic cost function by realizing two goals: minimizing the error between the outputs of the plant model (provided by linearization of the complete ego-vehicle model) and the references and enforcing the constraints. This control strategy is able to obtain prior knowledge of the linearized model by predicting its future behavior.
The preliminary steps considered in the design of the controller via the MPC method are:
- 1.
Modeling the system to control, described by Equations (
4a)–(
4c), (
6), (
7), (
8a), (
8b), whose states, inputs and outputs are defined in Equation (
9).
- 2.
Linearizing and discretizing the model, as described in Equations (
13a)–(
13c) and (
14a)–(
15b).
- 3.
Augmenting the model, by concatenating states and outputs of the linearized and discretized model [
38].
- 4.
Defining a cost function.
- 5.
Setting the constraints on input and/or output variables.
Then, an optimization algorithm finds the optimal solutions for the unconstrained case and for the constrained case valid for the considered model. In this way, an adaptive MPC on the time-varying linearized and discretized system is obtained.
The control system predicts the q outputs ( in this work) over an established time window. In particular, it predicts values ( in this work) of the outputs, where is called “prediction horizon”. Thus, MPC computes, at each iteration, a control trajectory (for each control variable) of samples, where ( in this work) is called “control horizon”. However, according to the Receding Horizon Control (RHC) approach, only the current p inputs ( in this work) are provided to the plant under control, i.e., the wheel torque and steering angle of the vehicle.
In order to obtain a sub-optimal solution, the procedure described in [
38] is used, based on Hildreth’s method, particularly useful for fast MPC implementation, as showed in [
39,
40,
41], both for automotive and other kind of applications (i.e., UAV and underwater vehicles).
In this work, the linearized and discretized model is augmented considering it as increment of the control signal
. Then, a quadratic cost function is considered, defined as:
where
is the vector of the current
q references replicated
times,
is the vector of the evaluated
output predictions, obtained through algebraic passages and
is the vector of control inputs over the control horizon [
38]. Furthermore,
is a diagonal matrix with suitable weights for each value of the control trajectory
. In detail,
, with
, where
(
in this work) refers to traction and braking wheel torque and
(
in this work) refers to steering at the wheels. The weights are here chosen based on the simulation results obtained by Model In the Loop (MIL) tests in MATLAB/Simulink (version R2020b) for the test cases discussed in the last section.
Within the MPC control framework, in addition to minimizing the index in (
16), inequality constraints for current inputs, future inputs and future outputs can be set according to [
38]. To reduce the computational load and given the RHC control logic, inequality constraints are set only for the current inputs and on the relative distance from the ahead vehicle, as:
In particular, in (
18), a soft constraint on
is imposed, to accept at most a term equal to
(
m in the case studies) below the theoretical safety distance
. Furthermore, the upper bound of
m is selected to keep the distance between the two vehicles limited.
The constrained problem can be solved only locally and, in order to obtain a fast computational burden with the objective to run adaptive MPC in a CAN cycle time ( ms), as will be shown in the results section, in this work Hildreth’s Quadratic Programming procedure is used. Then, defining as the first two elements of the obtained sub-optimal control, by adding to the set points of control variables, the corresponding vector of control inputs is obtained.
The overall flow chart for MPC implementation through model-based design approach and for MPC execution on a real MCU is shown in
Figure 3. Thus, at each time step the control algorithm waits for a new CAN message containing updated vehicle and environmental data (i.e., reference speed from C-ITS and/or ADAS sensors, road curvature, vehicle speed, lateral displacement, yaw angle error and relative distance). Then, when new data are available, the algorithm at first executes linearization and discretization, then the linearized model is augmented and MPC evaluates the global solution. If constraints are not violated, then the receding horizon allows to update the wheels torque and the steering angle at the wheels at the current time step, and then the execution returns to wait for a new CAN message. If there is a violation on constraints, then Hildreth’s method is executed in order to find a sub-optimal solution. Thus, the receding horizon is applied. Eventually, the execution restart waiting for a new CAN message.
3.3. Powertrain and Driveline Model
The vehicle investigated in this work presents a combined series-parallel powertrain composed of an ICE, two electric motor/generator units (
and
), a battery pack (
), a power converter (
), three clutches (
,
, and
), a differential (
) and three gear-boxes (
,
, and
). The powertrain schematic is depicted in
Figure 4. Either series or parallel driving can be activated, depending on the clutches position. Battery charging can be realized though
engaging
. Possible driving modes and the corresponding engagement/disengagement of the clutches are summarized in
Table 2. The presence of three clutches, on one side, complicates powertrain control, but, on the other side, avoids loadless operation when a unit is not used, reducing friction losses.
A static model of the powertrain and the driveline was implemented in the Simulink environment. It includes all components depicted in
Figure 4, where
,
, and
are described by their efficiency maps, while
and
are characterized by fixed parameters, listed in
Table 3.
3.4. Efficient Thermal Electric Skipping Strategy
The ETESS is a simplified logic that replaces the conventional power split approaches with an alternative utilization of the thermal and electric units for the fulfillment of the power demand at the vehicle wheels (
). The power demand is evaluated starting from the wheels torque provided by MPC as follows:
The choice between these two motors depends, at each time, on the comparison between the actual fuel rate of the
(when it operates to fully satisfy the power demand, if possible) and an equivalent fuel rate associated with the pure electric driving of the vehicle (
Figure 5).
The identification of the equivalent fuel rate (
) is based on the concept that, in a series configuration, the power delivered by the
to fulfill the power demand at the wheels was produced by the thermal engine in an undefined time, while working in its operating point of minimum brake specific fuel consumption (
). Since such power flux from the thermal engine to the wheels involves some losses in the
, in the
, in the
, in the
, in the
, and in the differential, the equivalent fuel rate in the pure electric mode is defined as follows:
where
is a tuning constant introduced to realize the energy balance for the battery between the beginning and the end of the driving cycle,
is the efficiency of the
,
is the efficiency of the
,
is the efficiency of the power converter,
is the
efficiency,
is the
efficiency and
is the efficiency of the differential. The Joule losses occurring into the battery pack are not explicitly considered in this formulation to preserve its mathematical simplicity.
The fuel rate in the pure thermal mode (
) only depends on the power demand, on the GB1 efficiency (
) and on the losses in the differential:
The is the actual brake specific fuel consumption of the ICE operating with the load and the speed related to the power demand at the wheels and the vehicle velocity, respectively.
The only degree of freedom for the evaluations of both
and
is the gear selection of the related gear-boxes. The latter is straightforwardly carried out by choosing the one that leads to the lowest fuel rate, complying with the constraints on minimum/maximum rotational speed and on maximum deliverable torque. Given the above definitions, the strategy for the selection between the pure electric mode and the thermal engine driving can be summarized by the following two inequalities
In summary, the ETESS method can be considered as a specialization of the ECMS, in which the only allowed power split values are either 0 or 1.
The introduction of such simplification is expected to involve a certain penalization of the fuel economy compared to the or the ECMS, but, on the other hand, a much reduced computational effort. In the ETESS approach, in fact, the choice between the pure thermal mode and the pure electric driving does not need any discrete map exploration: the operating point to be inquired for the evaluation of is univocally determined by the tractive power demand, the vehicle speed, and the losses along the driveline from the wheels to the engine (such evaluation has to be repeated only for the available gears of the gearbox linked to the ICE). Similarly, is univocally determined by the traction power demand, the vehicle speed, the losses along the driveline, and the dissipation in the electric units.
To avoid the onset of chattering, the actual switch between pure thermal driving to pure electric one (and the contrary) is realized only when the fuel rate advantage deriving from the driving mode switch exceeds the one in the current mode of a tunable quantity (about 0.22 kg/h in the present work).
The ETESS logic activates the parallel mode only when the is not able to fully supply the vehicle power demand by itself. In this case, the works at the maximum rated power, while the furnishes the remaining power to fulfill the power demand. The regenerative braking (which is activated when the wheel power demand becomes negative) is realized by the .
Since the aforementioned definition of the equivalent fuel rate needs an a priori knowledge of the vehicle speed to correctly select the
tuning constant, the ETESS, in the above-presented formulation, can be considered an offline strategy. For this reason, to realize a real-time implementation, Equation (
20) can be replaced by the following one:
where
is a vehicle-dependent constant (which is obtained by preliminary simulations performed in offline mode, where
is adjusted to realize a battery charge sustaining driving mode) and
is an adaptive correction depending on the current SoC of the battery [
42], whose dynamics equation is:
where
is the instantaneous battery current. This latter is estimated by a simple zeroth order model:
where
and
are assumed to be only function of the current SoC and
is the power exchanged by the battery (positive if drained from the battery).
evaluation is based on the mathematical function proposed in [
5,
6]. It is worth underlining that, differently from other methods (such as the “Rule-Based” strategies), the ETESS is versatile and also suitable to any HEV architecture. The reliability and effectiveness of ETESS have been verified in previous works along different driving cycles [
6,
43,
44].
5. Discussion
The paper presented a novel integrated control architecture featuring, at the same time, both motion and powertrain controls. The motion control is entrusted to an MPC strategy devoted to implementation of different ADAS functionalities (i.e., ACC, EEB, LKS). On the one hand, the choice of the MPC is motivated by the study on the survey in [
3], which indicates why this control strategy is the most suitable for CAVs. Another reason is that MPC allows one to solve a constrained optimization problem for MIMO systems, considering constraints on both outputs and control inputs. This feature is very useful from both autonomous and cooperative driving perspectives, due to the interaction between the vehicles and the surrounding environment (i.e., constraints on steering and safety distance, updated speed limits). It is also well known that using standard control techniques based on independent control algorithms and/or conventional controllers (i.e., PIDs) to solve multivariable tracking problems subject to specific constraints requires the usage of saturators, anti-wind up strategies, and decoupling regulators.
The present MPC is based on a simplified ego-vehicle model that allows the interface with a Smart Road, which provides, through C-ITS services, updated speed profiles (i.e., ISA), environmental and road conditions (i.e., wind speed, road friction, road slope and curvature), including model parameters needed by the control algorithm (i.e., air density, ahead vehicle mass and cross-area). As a novel contribution, the present MPC is coupled with ETESS, which is a hybrid powertrain energy management strategy devoted to delivering the required wheel torque while optimizing the fuel consumption. The design of ETESS proved to be a light energy management strategy that can be executed on the same MCU used for MPC.
Both MPC and ETESS have been designed through a model-based-design approach in Simulink. As known, this approach was extensively tested and supported by various standards (i.e., ISO 26262, AUTOSAR), for software development in automotive industry [
45,
46,
47]. The execution time of the whole strategy (MPC + EMS, comparing ETESS with ECMS) has been verified through PIL tests, using the ST Microelectronics NUCLEO-H743ZI2 equipped with MCU ARM STM32H743ZI2. The choice of this MCU was due to the failure of some tests conducted, in a previous stage, on another development board, the STM32F429I-DISC1, equipped with the MCU STM32F429ZI. On this board, it was not possible to execute MPC over a CAN cycle time (10 ms); in fact, in that case, the PIL test showed an average execution time of about 17 ms. The main difference between the two MCUs was the clock frequency: 180 MHz (STM32F429ZI) vs. 480 MHz (STM32H743ZI2). The price of the selected development board is lower than the previous one (on Mouser Europe [
48]): EUR 29.19 (STM32F429I-DISC1) vs. EUR 23.79 (NUCLEO-H743ZI2). Thus, with the selected MCU, the execution time of the whole strategy presented in this paper decreased of about 80%.
The results showed that ETESS is about 15 times faster than ECMS (see
Table 6); thus, considering that in general the MCUs are brought to the performance limit, this result is important as it allows the use of advanced control strategies (such as MPC) as an intermediate layer between the vehicle powertrain and the Smart Road. The achieved results encourage to continue the work, since PIL test demonstrated that motion and powertrain controls featured by the presented MPC coupled with ETESS, altogether, are executed in about 3.22 ms (see
Table 6). Thus, considering that the whole CAN cycle time for torque request and steering angle at the wheels is typically 10 ms, about 6.8 ms remain to implement, in the same MCU, other control algorithms, which will regard, in particular, path planning problems and eco-driving strategies. In this regard, path planning algorithms will allow the real-time estimation of the road curvature, which in this study is assumed to be known via simulation. Similarly, using real communication channels (e.g., cellular network or ad hoc Dedicated Short-Range Communication—DSRC) with the surrounding environment (in this work the Smart Road and V2V/V2I/I2V provide known information through simulation) and by knowing, for example, the origin–destination route with the associated road topology, the various alternative available routes and the state of road traffic, the implementation of eco-driving strategies could be possible on the same MCU. In this way, the same hardware architecture could be used, not only for motion and powertrain controls, but also for decision making and motion planning, covering the whole layer that in [
3] is named “Real-Time Control and Planning”.
In this work, a Smart Road has been simulated in order to provide the ahead vehicle with point-to-point speeds (i.e., ISA), wind velocity, road friction, road slope and air density. V2V communication has also been simulated for car-following data exchange (e.g., ahead vehicle information such as speed, mass, acceleration). This allowed us to test, very efficiently (PIL on inexpensive development boards), both motion and powertrain controls, considering two test scenarios based on a simple car-following (see
Figure 9,
Figure 10 and
Figure 11): one in the longitudinal direction only, involving the C-ITS service ISA and the ADAS functionalities EEB and ACC; another one in both longitudinal and lateral directions, involving road curvature, LKS and ACC. The results showed good tracking properties of the MPC in terms of reference speed, safety distance and lane keeping.
In order to check the effectiveness of the proposed controller against ego-vehicle model parameter uncertainties, robustness and sensitivity tests have been performed. Three parameters were subjected to variations: (i) drag coefficient
; (ii) cornering stiffness
; (iii) vehicle mass m. The robustness test (
Figure 12 and
Figure 13) shows good tracking performance for the vehicle speed and the achievement of the safety distance in the steady state. A slight deviation of about −5 mm from the nominal case in the steady state was induced by maximum parameters variations on the lateral displacement. This implies that in future developments, appropriate calibration processes should be carried out on the weights of the MPC, in order to try to improve this condition.
An additional test was performed in order to check the sensitivity of the MPC with respect to single parametric variations. The results shown in
Table 8,
Table 9,
Table 10,
Table 11,
Table 12 and
Table 13 show that, among the tested parameter configurations, the highest deviations from the reference are reached with the the maximum load (
).
All in all, considering the RMSE index, the above variations are quite contained, except for the wheel power, which is obviously higher if the vehicle load is greater. For future developments, a calibration process on the parameters of the MPC (i.e., weights, prediction and control horizons) should be performed in order to reduce RMSE for , and for the full load condition. The cornering stiffness specifically influences some variables, that are lateral displacement and wheel power. The variation of determines RMSE to be quite contained, slightly affecting the steady state error. Eventually, the variations of the drag coefficient affect the wheel power more significantly.
At the current state, the present work is part of the research project named “Borgo 4.0”. This project has the ambitious objective, by the end of 2023, to test cooperative driving and energy management strategies in the real environment of Lioni, a small town in the province of Avellino (south Italy). In particular, the tasks of the authors on the aforementioned research project, in collaboration with NetCom Engineering S.p.A. [
49], will regard the development of advanced control strategies for motion planning and energy management (on HEVs and EVs) to be tested in real-scenarios, such as:
Furthermore, NetCom Engineering has to develop an IoT gateway enabling the real communication with the Smart Road infrastructure, providing V2V, V2I and I2V communications. Thus, the selected MCU can be a hardware module of the aforementioned gateway.
Of course, a subsequent development will involve the validation of the selected MCU, using more advanced testing techniques, such as HIL with real-time simulators, and real communication channels (e.g., cellular, DSRC). In this context, the possibility to adopt a more powerful MCU will be considered. However, the advantage of this strategy has been also its development by model-based-design approach. In this way, even if future developments will require a different MCU, the control algorithm and the correspondent Simulink modules will not require substantial modifications, since only a different code generation will be requested (i.e., a different embedded coder or the same one used in this work, but applied to a more powerful STMicroelectronics MCU).
For this reason, the presented approach is general and can be extended for future developments, also considering any kind of vehicle and powertrain.
6. Conclusions
The proposed MPC featured as an intermediate layer between vehicle powertrain and Smart Road. The MPC was integrated with an energy management strategy named ETESS in order to allow, simultaneously, both motion and powertrain controls.
The Smart Road and V2V/V2I/I2V information (i.e., ISA, wind velocity, road friction, air density and car-following data exchange, such as ahead vehicle speed, mass, acceleration) were assumed to be known via simulation. Thus, the objective was to demonstrate the real-time execution on a real MCU of coupled MPC and ETESS through PIL testing, in order to allow the extension of the work for further developments.
Below, the main outcomes are summarized:
The average execution time of MPC + ETESS on the same MCU (STM32H743ZI2) was about 3.22 ms and therefore well below the typical CAN cycle time for torque request and steering angle, which is 10 ms.
ETESS was 15 times faster than ECMS; thus, this encourages the implementation of further control strategies on the same MCU, in order to reach additional real-time features, such as path planning and eco-driving.
Along representative maneuvers, MPC showed good tracking properties of reference speed (with an error below the 0.1% in the steady state) and lane keeping (error below 1 cm for the lateral displacement and 0.025° for the yaw angle). MPC allowed us to keep a relative distance greater than the minimum safety distance during braking phases and follows the theoretical safety distance in the steady state (with an error below 0.1%).
The robustness of MPC against ego-vehicle model parameters uncertainties (drag coefficient, cornering stiffness and vehicle mass) showed good tracking performance of the vehicle speed and a slight deviation (−5 mm; the maximum allowed is equal to 35 cm) of the lateral displacement at the maximum parameters variations (, , ). The ICE activation occurred, respectively, 14 s earlier (maximum parameters variations) and 9 s later (minimum parameter variations), depending on the battery discharge rate during the early stage of the maneuver.
The sensitivity tests of MPC against the individual variation of single parameter of the ego-vehicle model showed a relevant influence of the maximum vehicle load () towards all variables: lateral displacement ( cm), vehicle speed ( km/h), relative distance ( m) and wheels power ( kW). With the minimum cornering stiffness , the highest impact occurred for the lateral displacement ( cm), while with the maximum one , the highest influence was on the wheels power ( kW). The wheels power was also significantly influenced by the drag coefficient, showing a kW and a kW. Considering the RMSE indices, the variations were quite contained, except for the wheels power, which, as expected, was higher if the vehicle load and drag coefficient were greater.
The implementation of MPC and ETESS through model-based-design approach allows to easily adapt the corresponding Simulink modules for other MCUs. Nevertheless, in the case of further developments, MCUs exhibiting better performances could be required and an appropriate calibration process on the MPC parameters (weights, control and prediction horizons) could be conducted to improve its robustness and sensitivity. In particular, the MPC calibration appears appropriate to reduce the 1.89 cm gap with respect to the nominal case, which has been obtained for the lateral displacement with lower tire cornering stiffness.
The next developments of this work will include the connection between the proposed integrated motion and powertrain control strategies with path planning and C-ITS services, available through V2X communication. Moreover, the HIL testing through a co-simulation environment will be performed to consider the interaction between the ego-vehicle, other vehicles and the Smart Road using real communication channels (e.g., cellular network, DSRC). The HIL testing will also be necessary to overcome the limitations of the current testing approach (PIL), which is based on asynchronous communication between a PC-Host and the selected development board (NUCLEO-H743ZI2), while allowing the verification robust execution in real-time. Through HIL test it will be possible to understand, by implementing other additional control strategies for path planning and eco-driving, whether the selected MCU can be confirmed. If it will be necessary to change MCU, by using the model-based-design approach, the implemented control modules will not change. In addition, further developments will regard the design of other strategies for motion and powertrain controls, considering, for example, the use of other MPC types, in order to compare them with the present adaptive MPC. Possible alternatives could be: robust MPC, NLMPC and Data-Driven MPC, on which there are promising studies in the literature, as in [
50,
51,
52].
Eventually, the presented strategy is part of the research project Borgo 4.0, in partnership with NetCom Engineering. This project foresees real road test by the end of 2023, in order to verify motion, energy management, decision making and path planning strategies in different scenarios (such as intersection management, rear-end collisions and eco-driving) by using the IoT gateway that will be designed by NetCom Engineering. Thus, the selected MCU could be an hardware module of the aforementioned IoT gateway.