Keywords

1 Introduction

Since 2014, the EU has mandated vehicle stability controllers (VSCs), enhancing active safety during emergency manoeuvres, through the limitation of the yaw rate error, sideslip angle, and longitudinal tyre slip [1, 2]. While these systems are effective in supporting the average human driver, they may be overly conservative for highly automated vehicles (AVs) [3]. In parallel, powertrain electrification and active chassis control systems offer new AV control opportunities [4]. A current trend in AV research involves emulating expert driving techniques, such as drifting, by using path tracking (PT) controllers that push the vehicle beyond the conventional VSC-related stability constraints, potentially improving road safety [5]. Several PT algorithms from the literature, e.g., [6, 7], achieve controlled drifting by tracking dedicated sideslip angle and yaw rate profiles, in addition to the reference trajectory. However, such controllers are not designed to induce drifting only when necessary to track a challenging trajectory, and are often demonstrated in scenarios with negligible vehicle speed variations or increasing speed, along circular paths or during drift parking, typically with rear-wheel-drive AVs [8, 9]. On the contrary, typical real-world emergency manoeuvres involve significant speed reductions through braking, imposed either by the human/automated driver and/or the VSC. Although the recent studies in [5] and [10] demonstrate the safety benefits of autonomous drifting in realistic scenarios, the literature lacks a performance assessment of different chassis actuation suites, and especially rear-wheel-steering (RWS), in terms of accident avoidance through AV control beyond the VSC-related boundaries. This paper targets the gap by proposing an NMPC algorithm that integrates four-wheel-steering, longitudinal tyre force distribution, and direct yaw moment (DYM) actuation. Simulation results with a high-fidelity model along two challenging manoeuvres show the controller’s capability to perform drifting, and the benefit of rear steering actuation for achieving tighter cornering.

2 Control Architecture

Three alternative NMPC PT formulations are considered: i) \(NMP{C}_{{M}_{z},{\delta }_{r}}\), which is the novelty of the study, and controls (independently from each other) the time derivatives of the front and rear steering angles, \({\dot{\delta }}_{f}\) and \({\dot{\delta }}_{r}\); the time derivative of the longitudinal tyre force on the front axle, \({\dot{F}}_{x,f}\); the front-to-total force distribution factor in braking, \({p}_{b}\); and the time derivative of the DYM, \({\dot{M}}_{z}\); ; ii) \(NMP{C}_{{M}_{z}}\), which, compared to \(NMP{C}_{{M}_{z},{\delta }_{r}}\), excludes \({\dot{\delta }}_{r}\) control; iii) \(NMP{C}_{bas}\), which, compared to \(NMP{C}_{{M}_{z}},\) excludes \({\dot{M}}_{z}\) and \({p}_{b}\) control. The control allocation (CA) algorithm is detailed in [5], and is integrated with a rule-based VSC, including a PID anti-lock braking system (ABS). In the \(NMP{C}_{{M}_{z},{\delta }_{r}}\) and \(NMP{C}_{{M}_{z}}\) simulations, the VSC intervention thresholds are relaxed, to allow operation beyond the limits of handling.

2.1 Prediction Model Formulations

The prediction models are based on the single-track formulation in [5]. For brevity, only the updated longitudinal and lateral force balance and yaw moment balance equations for the \(NMP{C}_{{M}_{z},{\delta }_{r}}\) case are reported:

$$ \begin{aligned} & \dot{v}_{x} = \frac{1}{m}[F_{x,f} {\text{cos}}\left( {\delta_{f} } \right) - F_{y,f} {\text{sin}}\left( {\delta_{f} } \right) + F_{x,R} {\text{cos}}\left( {\delta_{r} } \right) \\ & \,\; - F_{y,r} {\text{sin}}\left( {\delta_{r} } \right) - F_{x,Mz} - F_{drag} - F_{roll} + mv_{y} \dot{\psi }{ }] & \\ & \dot{v}_{y} = \frac{1}{m}[F_{x,f} {\text{sin}}\left( {\delta_{f} } \right) + F_{y,f} {\text{cos}}\left( {\delta_{f} } \right) \\ & \;\; + F_{x,r} {\text{sin}}\left( {\delta_{r} } \right) + F_{y,r} {\text{cos}}\left( {\delta_{r} } \right) - mv_{x} \dot{\psi }] \\ & \ddot{\psi } = \frac{1}{{I_{z} }}[F_{x,f} \sin \left( {\delta_{f} } \right)l_{f} { } + F_{y,f} \cos \left( {\delta_{f} } \right)l_{f} \\ & - F_{y,r} {\text{cos}}\left( {\delta_{r} } \right)l_{r} { } - F_{x,r} {\text{sin}}\left( {\delta_{r} } \right)l_{r} + M_{z} ] \\ \end{aligned} $$
(1)

where \(m\) is the vehicle mass; \({I}_{z}\) is the yaw mass moment of inertia; \({l}_{f}\) and \({l}_{r}\) are the front and rear semi-wheelbases; \({F}_{drag}\) and \({F}_{roll}\) are the aerodynamic drag and rolling resistance force; \({F}_{x,i}\) and \({F}_{y,i}\) are the longitudinal and lateral tyre forces of the axle \(i\), where the subscript \(i=f,r\) refers to the front or rear axles; and \({M}_{z}\) is the direct yaw moment generated through the actuation of the friction brakes, while \({F}_{x,{M}_{z}}\) is the corresponding longitudinal tyre force contribution. The lateral axle forces, \({F}_{y,i,}\), are calculated through a simplified version of the Pacejka magic formula, whose vertical tyre force inputs account for both the static contribution and the longitudinal load transfer, based on the measured longitudinal acceleration, \({a}_{x,meas}\).

2.2 Optimal Control Problem

At each time step, the NMPC algorithm computes an optimal control sequence that minimizes a cost function, see its discrete form in [5], based on the outputs from the prediction models, which are expressed through the following continuous time formulation:

$$ \dot{x}\left( t \right) = f\left( {x\left( t \right),u\left( t \right),w\left( t \right)} \right) $$
(2)

where \(x\) is the state vector, and \(u\) is the control input vector, which, for the three considered controller configurations, are expressed as:

$$ \begin{array}{*{20}c} {x_{{M_{z} ,\delta_{r} }} = \left[ {v_{x} ,v_{y} ,\dot{\psi },s,e_{y} ,e_{\psi } ,\delta_{f} ,F_{x,f} , M_{z} ,\delta_{r} } \right]} & {u_{{M_{z} ,\delta_{r} }} = \left[ {\dot{\delta }_{f} ,\dot{F}_{x,f} ,p_{b} ,\dot{M}_{z} ,\varepsilon_{Mz} ,\dot{\delta }_{r} } \right]} \\ {x_{{M_{z} }} = \left[ {v_{x} ,v_{y} ,\dot{\psi },s,e_{y} ,e_{\psi } ,\delta_{f} ,F_{x,f} , M_{z} } \right]} & {u_{{M_{z} }} = \left[ {\dot{\delta }_{f} ,\dot{F}_{x,f} ,p_{b} ,\dot{M}_{z} ,\varepsilon_{Mz} } \right]} \\ {x_{bas} = \left[ {v_{x} ,v_{y} ,\dot{\psi },s,e_{y} ,e_{\psi } ,\delta_{f} ,F_{x,f} } \right]} & {u_{bas} = \left[ {\dot{\delta }_{f} ,\dot{F}_{x,f} } \right]} \\ \end{array} $$
(3)

where s is the distance along the path; \({e}_{y}\) is the lateral position error; \({e}_{\psi }\) is the heading angle error; and \({\varepsilon }_{Mz}\) is the slack variable associated with a soft constraint on the DYM. The online data vector, \(w\), is the same for \(NMP{C}_{{M}_{z},{\delta }_{r}}\) and \(NMP{C}_{{M}_{z}}\), i.e., \({w}_{{M}_{z},{\delta }_{r}}=\)

\({w}_{{M}_{z}}=\left[{a}_{x,meas},\mu , {\rho }_{ref},{M}_{z,min},{M}_{z,max}\right]\), where \(\mu \) is the tyre-road friction factor, which is assumed constant along the prediction horizon (\({H}_{p}\)), while the reference road curvature (\({\rho }_{ref}\)) and the maximum and minimum DYM values (\({M}_{z,max}\) and \({M}_{z,min}\)) vary according to [5]. In \(NMP{C}_{bas}\), \(w\) excludes \({M}_{z,min}\) and \({M}_{z,max}\). The output vectors and their reference values include the PT error variables and the states associated with the control inputs:

$$ \begin{array}{*{20}c} {z_{{M_{z} ,\delta_{r} }} = \left[ {v_{x} ,e_{y} ,e_{\psi } ,\delta_{f} ,\delta_{r} ,F_{x,f} ,M_{z} } \right]} & {z_{{M_{z} ,\delta_{r} ,ref}} = \left[ {v_{x,ref} ,0,0,0,0,0,0} \right] } \\ {z_{{M_{z} }} = \left[ {v_{x} ,e_{y} ,e_{\psi } ,\delta_{f} ,F_{x,f} ,M_{z} } \right]} & {z_{{M_{z} ,ref}} = \left[ {v_{x,ref} ,0,0,0,0,0} \right]} \\ {z_{bas} = \left[ {v_{x} ,e_{y} ,e_{\psi } ,\delta_{f} ,F_{x,f} } \right]} & {z_{bas,ref} = \left[ {v_{x,ref} ,0,0,0,0} \right]} \\ \end{array} $$
(4)

where the reference longitudinal speed, \({v}_{x,ref}\), is assumed to be known and variable along \({H}_{p}\). For all controllers, hard constraints are set on the steering angles, the front longitudinal tyre force, and their variation rates, as well as on the rear longitudinal tyre force:

$$ \begin{array}{*{20}{l}} { - {\delta _{i,max}} \leqslant {\delta _i} \leqslant {\delta _{i,max}}} \\ { - {\mu _{id}}{F_{z,f}} \leqslant {F_{x,f}} - {F_{x,{M_z}}}\frac{{{F_{z,f}}}}{{{F_{z,f}} + {F_{z,r}}}} \leqslant {\mu _{id}}{F_{z,f}}} \\ { - {{\dot \delta }_{i,max}} \leqslant {{\dot \delta }_i} \leqslant {{\dot \delta }_{i,max}}} \\ {{{\dot F}_{x,f,min}} \leqslant {{\dot F}_{x,f}} \leqslant {{\dot F}_{x,f,max}}} \\ { - {\mu _{id}}{F_{z,r}} \leqslant {F_{x,r}} - {F_{x,{M_z}}}\frac{{{F_{z,r}}}}{{{F_{z,f}} + {F_{z,r}}}} \leqslant {\mu _{id}}{F_{z,r}}} \end{array} $$
(5)

where \({\mu }_{id}\) is an ideal friction factor, which marginally overestimates the real one used in the high-fidelity vehicle model to avoid underbraking, while the slip ratios are limited by the ABS, with relaxed intervention thresholds in case of \(NMP{C}_{{M}_{z},{\delta }_{r}}\) and \(NMP{C}_{{M}_{z}}\); and the term \({F}_{x,{M}_{z}}\) is present only in \(NMP{C}_{{M}_{z},{\delta }_{r}}\) and \(NMP{C}_{{M}_{z}}\).\(NMP{C}_{{M}_{z}}\) and \(NMP{C}_{{M}_{z},{\delta }_{r}}\) also include a hard constraint on \({p}_{b}\), a soft constraint on \({M}_{z}\), and a hard constraint on \(\dot{{M}_{z}}\):

$$ \begin{array}{*{20}c} {p_{b,min} \le p_{b} \le p_{b,max} } \\ { - \varepsilon_{Mz} + M_{z,min} \le M_{z} \le M_{z,max} + \varepsilon_{Mz} ,\,{\text{with}}\,\varepsilon_{Mz} \ge 0} \\ {\dot{M}_{z,min} \le \dot{M}_{z} \le \dot{M}_{z,max} } \\ \end{array} $$
(6)

where \({M}_{z,min}\) and \({M}_{z,max}\) are computed by the CA algorithm, based on the prediction of the control inputs at the previous time step.

3 Model Validation and Simulation Results

3.1 Case Study Vehicle

A four-wheel-drive electric vehicle (EV) prototype by IFEVS, with a centralized on-board electric machine per axle, is used as case study, see Fig. 1a. The EV is equipped with: i) a set of vehicle dynamics sensors, e.g., to measure the individual wheel speeds and the longitudinal and lateral velocity components; ii) an integrated GPS device with inertial measurement unit; iii) a modified commercial VSC unit to independently control the friction brake torque of each corner; and iv) a dSPACE MicroAutoBox III system for rapid control prototyping. The vehicle simulation model was implemented in the IPG CarMaker environment, and was experimentally validated along a handbrake manoeuvre, see Fig. 1b. The very good match between the experiments and the high-fidelity and prediction model results confirms: i) the reliability of the CarMaker model as a control system assessment tool; and ii) the ability of the proposed prediction models to accurately capture the system dynamics at the limit of handling.

Fig. 1.
figure 1

(a) Case study EV prototype. (b) Time profiles of the hand-brake manoeuvre inputs, i.e., steering wheel angle \({\delta }_{sw}\), wheel torque \({T}_{wh}\), and braking pressures \({P}_{brk}\), along with the associated sideslip angle \(\beta \), yaw rate \(\dot{\psi }\), and lateral acceleration \({a}_{y}\). IPG: CarMaker simulation model results; Exp.: experimental results; Pred. Mod.: prediction model results. The notations ‘fl’, ‘fr’, ‘rl’ and ‘rr’ refer to the front left, front right, rear left, and rear right corners.

3.2 Simulation Results

The NMPC implementations were evaluated along two manoeuvres, i.e., a 135-deg turn and a U-turn with braking from an initial speed of 45 km/h. For \(NMP{C}_{{M}_{z},{\delta }_{r}}\), different RWS angle limits, equal to 5, 10, and 15 deg, were set. Although higher than those for typical RWS systems, these values were selected to assess the potential advantages of enhanced rear steering capabilities. The 135-deg turn results are reported in Fig. 2a. The vehicle with \(NMP{C}_{bas}\) significantly deviates from the reference trajectory, and exits the turn with unsafe lateral and orientation errors. On the contrary, the drifting behaviour induced by \(NMP{C}_{{M}_{z}}\) and \(NMP{C}_{{M}_{z},{\delta }_{r}}\) enables the EV to effectively complete the manoeuvre. The DYM interventions create an asymmetric braking force distribution between the EV sides, resulting in increased yaw rate and rear slip angle magnitudes, which enhance manoeuvring agility. However, the \({M}_{z}\) profile requested by the PT controller is very different from the one generated by the vehicle through the CA algorithm, see the mismatch between the ‘NMPC’ and ‘Plant’ curves in the \({M}_{z}\) plot. This is caused by the absence of the lateral load transfer in the prediction model, and the purposely relaxed constraints on the longitudinal force and DYM, to fully utilise the tyre-road friction capability. While the \({\delta }_{r}\) actuation does not improve performance in the 135-deg turn, the counterphase actuation of \({\delta }_{f}\) and \({\delta }_{r}\) can facilitate vehicle oversteer [11], with potential benefits during more aggressive manoeuvres, such as the U-turn in Fig. 2b, for which a higher initial destabilizing effect is desirable. Since the inner wheel tends to be saturated during high lateral acceleration manoeuvring, the DYM intervention struggles generating the destabilizing effect required to induce controlled drifting, which, instead, can be more effectively induced with the RWS intervention. As a result, \(NMP{C}_{{M}_{z},{\delta }_{r}}\) generates higher yaw rates, reducing the DYM intervention as well as the lateral and speed tracking errors. For \(NMP{C}_{{M}_{z}}\) and \(NMP{C}_{{M}_{z},{\delta }_{r}}\), Table 1 includes a set of PT key performance indicators (KPIs), including the maximum and root mean square (RMS) errors of the lateral position and speed, along with the maximum sideslip angle magnitude, indicating the extent of the controlled drifting behaviour. The RWS actuation of \(NMP{C}_{{M}_{z},{\delta }_{r}}\) reduces the lateral error by ~1.8 m during the U-turn test, compared to DYM intervention alone of \(NMP{C}_{{M}_{z}}\). The best trade-off between the lateral and speed tracking errors is achieved with a maximum rear steering angle magnitude of 10 deg. A further increase to 15 deg results in higher \({\left|\beta \right|}_{max}\) (up to 44 deg), lower \(RM{S}_{{e}_{{v}_{x}}}\), and increased \({\left|{e}_{y}\right|}_{max}\)(by 0.17 m).

Fig. 2.
figure 2

Simulation results for (a) the 135-deg turn and (b) the U-turn, for \(NMP{C}_{bas}\), \(NMP{C}_{{M}_{z}}\), and \(NMP{C}_{{M}_{z},{\delta }_{r}}\) with maximum RWS angle constraints equal to 5, 10, and 15 deg.

Table 1. KPIs along the 135 deg-turn and U-turn (the best values are highlighted in bold).

4 Conclusion

The study introduced a nonlinear model predictive controller (\(NMP{C}_{{M}_{z},{\delta }_{r}}\)) for the concurrent actuation of the front and rear steering angles, the total longitudinal tyre force and its distribution between the axles, as well as the direct yaw moment, to execute drifting manoeuvres when beneficial to the path tracking (PT) performance in emergency conditions. The simulation results, based on an experimentally validated vehicle model, highlight that: i) drifting is very effective in dealing with challenging trajectories that PT controllers coupled with conventional vehicle stability controllers cannot achieve (see the \(NMP{C}_{bas}\) results), thereby enhancing the collision avoidance capability; and ii) in the more demanding scenario, i.e., the U-turn test, the rear steering actuation of \(NMP{C}_{{M}_{z},{\delta }_{r}}\) significantly enhances the tracking performance, by reducing the maximum lateral error by ~1.8 m compared to \(NMP{C}_{{M}_{z}}\).