1 Introduction

Vehicle automation and active safety systems have gained increased research interest in the last two decades. Many advances in advanced driver assistant systems (ADAS) and active safety systems have been developed and introduced by the automotive industry, such as lane departure warning, lane keeping assist, yaw stability control, adaptive cruise control, evasive steering assist, and much more. In real world applications, environmental variables and disturbances, such as, tire-road friction coefficient, road-bank angle, road slope, and wind deteriorate the performance of these control systems by causing inconsistent behavior and instability in some cases. The performance of these control systems can be improved significantly if they can be made “environment adaptive”. This can be achieved by real-time estimation of these environmental variables.

This paper focuses on real time estimation of road bank angle and side slip angle. Road bank angle can significantly deteriorate the behavior of automatic steering control systems, such as lane keeping assist, lane centering, and evasive steering assist, as well as vehicle stability control systems. Providing real-time information about road bank angle helps such control systems to maintain a consistent and stable behavior.

Side slip angle feedback is very important for yaw stability control systems to control it from becoming too large, especially on low-friction road surfaces to prevent the vehicle from skidding and spinning. Many yaw stability control systems depend on the yaw rate feedback only for enhancing vehicle stability. In this case, the control system ensures that the vehicle yaw rate does not exceed a desired value. However, on low surface friction roads, the yaw rate by itself is not sufficient to stabilize the vehicle, and it is also necessary to add the side slip angle as feedback and control it to prevent it from becoming too large. A two large slip angle reduces the tire ability to generate lateral forces and significantly degrades the Behavior of the control system and can cause instability. Knowledge of side slip angle is also necessary for active roll stability control systems that prevent the vehicle from rolling over.

Global Positioning System (GPS) combined with inertial measurement unit methods for estimating road bank angle and side slip angle are widely used, as in [1,2,3,4,5]. The limitation of GPS-based methods in general is that they are unreliable in urban driving environments where tall buildings and urban canyons can prevent access to GPS satellite signals and that leads to faulty estimates, that could cause instability in control systems that are using these estimates. Another disadvantage of the GPS-inertial measurement unit based methods is that the inertial sensors often have to be of very high quality in order to obtain a reasonable drift-free estimates. High quality inertial measurement units are extremely expensive to be used in current road vehicles. In [6], lateral disturbance estimator for side wind force and road bank angle is developed using the linear Kalman Filter (KF). The two degrees of freedom linear bicycle vehicle model is used. This model is linear assuming the longitudinal speed of the vehicle is constant, but in reality, it is constantly changing in highway driving, which requires tuning KF separately for each speed in the speed range (usually 0-130kph) and then construct look up tables for Kalman gains based on speed, which is a time-consuming process. In our method, we are also using the same model, but we are assuming that the longitudinal speed is varying and we treat it as a third state, which makes the model no longer linear. We linearize the model using Taylor series expansion and then we use extended Kalman filter (EKF) instead of Kalman filter. This avoids the time-consuming tuning process of the Kalman gains for different speeds, and eliminates the need for look up tables. Also, in [6], the measurement model consists of the self-aligning torque estimate with the yaw rate measurement. An accurate estimate of self-aligning torque requires estimating lateral forces, normal forces, tire slip angle, mechanical trail, and pneumatic trail first. Also, self-aligning torque estimation is tire parameters dependent, which means that if we change the tire type in the vehicle, we have to change the parameters in the estimator, which is impractical. In our approach, we are fusing the lateral acceleration measurement with the yaw rate measurement. Both measurements can be easily obtained from onboard vehicle inexpensive sensors. In [7, 8], the recursive least squares (RLS) method is used to estimate the road bank angle with other variables. The disadvantage of RLS is its reliance on a persistent excitation input signal, if the input signals to the estimator are not dynamically persistent enough, the estimate will diverge. In [9], a plant-inverse based technique to estimate and compensate for the lateral disturbances is developed. This method treats the lateral disturbance as indeterministic, which means that the disturbance can be coming from any source, it does not distinguish what the disturbance is, which means there is no explicit estimate of road bank, which makes this method less versatile than methods that treat the disturbance as deterministic. In [10], A constrained dual Kalman filter based on pdf truncation for estimation of vehicle parameters and road bank angle is developed. In [11], yaw rate and roll rate are fused to estimate the bank angle and road grade. In [12], a proportional–integral H filter based on the game theory approach is developed for bank angle estimation. In [13], a multiple Model filter with two modes is introduced for estimating the vehicle yaw-rate, lateral velocity, road bank angle and crosswind force. In [14], the average lumped LuGre tire model is used to estimate the road bank angle. In [15], the road bank angle is computed from the IMU using three axles acceleration measurements lateral acceleration, longitudinal acceleration, and vertical acceleration. The road bank is computed directly from a kinematic relationship that combines these three measurements. In [16], vehicle roll angle is estimated taking the road bank angle effect in consideration. The bank angle is treated as a general unknown input disturbance term that is rejected by the roll bank angle observer, but not explicitly estimated. Deep Nueral Networks (DNN) for side slip angle estimation were investigated in [17,18,19]. DNN based methods may raise computational complexity problems. In [20], a Factor-Graph-Based approach to estimate vehicle sideslip angle is used.

This paper develops an approach to estimate road-bank angle and side slip angle in real time by combining lateral acceleration and yaw rate measurements from IMU with the dynamical single track model. The single track model is considered linear based on the assumption that the longitudinal speed is constant. In our method, we assume that the longitudinal speed is varying, not constant, which makes the model no longer linear because its equations are divided by longitudinal speed. The speed is considered as a third state that is updated at every time step. We linearize the model using Taylor series expansion and we use EKF for the estimation. This way, we avoid the time consuming tuning process to come up with look up tables based on speed that has to be done if we assume the longitudinal speed is constant and use the linear Kalman filter. The developed estimation algorithm was validated by experimental results on a test vehicle. It was verified that the algorithm provides reliable road bank angle and slip angle estimation that can be be potentially used in vehicle stability controllers.

The paper is organized as follows, the vehicle model is explained in Section 2, followed by the observer design in Section 3, and then experimental results in Section 4.

2 Vehicle Model

The single track model for lateral vehicle is considered for the observer design. In this model, the left and right front tires are represented in one single front tire and similarly the left and right rear tires are represented by one central rear tire. The model has two degrees of freedom, vehicle sideslip angle \(\beta\), which is defined as the angle between the longitudinal axis of the vehicle and the orientation of the vehicle longitudinal velocity vector v at the center of gravity (CG), and the vehicle yaw rate \(\dot{\psi }\), which is defined as the rate of change of the vehicle yaw angle. The vehicle yaw angle \(\psi\) is measured with respect to the global X axis. The longitudinal speed is assumed to be constant in the single track model, which makes the model linear The model is illustrated in Fig. 1, taken from [21].

Fig. 1
figure 1

Single track model

The lateral dynamics of the vehicle can be well represented using the side slip angle and the yaw rate of the vehicle, described by the differential equations below [21, 22]

$$\dot{\beta }=\frac{{a}_{11}}{v}\beta +\left(\frac{{a}_{12}}{{v}^{2}}-1\right)\dot{\psi }+\frac{{b}_{1}}{v}\delta$$
(1)
$$\ddot{\psi }={a}_{21}\beta +\frac{{a}_{22}}{v}\dot{\psi }+{b}_{2}\delta$$
(2)

where, 

$$\begin{array}{ccc}\alpha_{11}=-\frac{\left(C_r+C_f\right)}m&\alpha_{12}=\frac{C_rl_r-C_fl_f}m&b_1=\frac{C_f}m\\\alpha_{21}=\frac{C_rl_r-C_fl_f}{I_z}&\alpha_{22}=\frac{C_rl_r^2+C_fl_f^2}{I_z}&b_2=\frac{C_fl_f}{I_z}\end{array}$$

where \({l}_{f},{l}_{r}\) are the distances from CG to front and rear tires, respectively and \({I}_{z}\) is the vehicle moment of inertia about the \(Z\) axis. \({C}_{f},{C}_{r}\) are the cornering stiffnesses at the front and rear tires, respectively. \(m\) is the mass of the vehicle.

The state space representation of the model is given by,

$$\left[\begin{array}{c}\dot{\beta }\\ \ddot{\psi }\end{array}\right]=\left[\begin{array}{cc}\frac{{a}_{11}}{v}& \frac{{a}_{12}}{{v}^{2}}-1\\ {a}_{21}& \frac{{a}_{22}}{v}\end{array}\right]\left[\begin{array}{c}\beta \\ \dot{\psi }\end{array}\right]+\left[\begin{array}{c}\frac{{b}_{1}}{v}\\ {b}_{2}\end{array}\right]\delta$$
(3)

where \({\left[\beta\ \dot{\psi }\right]}^{\prime}\) is the state vector and \(\delta\) is the control input.

Considering the influence of road bank force, (1) becomes,

$$\dot{\beta }=\frac{{a}_{11}}{v}\beta +\left(\frac{{a}_{12}}{{v}^{2}}-1\right)\dot{\psi }+\frac{1}{mv}{F}_{b}+\frac{{b}_{1}}{v}\delta$$
(4)

where, \({F}_{b}=mg \ \text{sin}\left(\theta \right)\) is the road bank force, and \(\theta\) is the road bank angle as illustrated in Fig. 2, taken from the web, where \({F}_{N}=mg\) is the normal force.

Fig. 2
figure 2

Illustration of road bank angle effect

The vehicle yaw dynamics are not influenced by the road bank force, hence (2) stays the same even in the presence of road bank force.

The resulting state space representation of the model with road bank angle consideration is given by,

$$\left[\begin{array}{c}\dot{\beta }\\ \ddot{\psi }\\ {\dot{F}}_{b}\end{array}\right]=\left[\begin{array}{ccc}\frac{{a}_{11}}{v}& \frac{{a}_{12}}{{v}^{2}}-1& \frac{1}{mv}\\ {a}_{21}& \frac{{a}_{22}}{v}& 0\\ 0& 0& 0\end{array}\right]\left[\begin{array}{c}\beta \\ \dot{\psi }\\ {F}_{b}\end{array}\right]+\left[\begin{array}{c}\frac{{b}_{1}}{v}\\ {b}_{2}\\ 0\end{array}\right]\delta$$
(5)

The model is discretized for the EKF implementation using euler discretization method as,

$$\begin{array}{l}f\left(\mathbf x\right)={\mathbf x}_{\mathbf k\boldsymbol+\mathbf1}\\\left\{\begin{array}{l}f_1\left(\mathbf x\right)=\beta_{k+1}=\beta_k+T_s(\frac{\alpha_{11}}{v_k}\beta_k+\left(\frac{\alpha_{12}}{v_k^2}-1\right){\dot\psi}_k+\frac{F_{bk}}{mv_k})+T_s(\frac{b_1}{v_k}\delta)\\f_2\left(\mathbf x\right)={\dot\psi}_{k+1}={\dot\psi}_k+T_s(\alpha_{21}\beta_k+\frac{\alpha_{22}}{v_k}{\dot\psi}_k)+T_s(b_2\delta)\\f_3\left(\mathbf x\right)=v_{k+1}=v_k\\\begin{array}{l}f_4\left(\mathbf x\right)=F_{bk+1}=F_{bk}\\\end{array}\end{array}\right.\end{array}$$
(6)

where \({\mathbf x}_k=\left[\beta_k\;{\dot\psi}_k\;v_k\;F_{bk}\right]'\) is the state vector after discretization.

3 Observer Design

In this section, we are going to design an observer to estimate the lateral vehicle state, body side slip angle and yaw rate, and the disturbance caused by road bank forces using EKF. Since we are not assuming that the longitudinal speed \(v\) is constant, this makes the model no longer linear and has to be linearized.

The model is linearized using the first order Taylor series expansion as given below,

$${\mathbf A}_k=\begin{bmatrix}\frac{\partial f_1}{\partial x_1}&\frac{\partial f_1}{\partial x_2}&\frac{\partial f_1}{\partial x_3}&\frac{\partial f_1}{\partial x_4}\\\frac{\partial f_2}{\partial x_1}&\frac{\partial f_2}{\partial x_2}&\frac{\partial f_2}{\partial x_3}&\frac{\partial f_2}{\partial x_4}\\\frac{\partial f_3}{\partial x_1}&\frac{\partial f_3}{\partial x_2}&\frac{\partial f_3}{\partial x_3}&\frac{\partial f_3}{\partial x_4}\\\frac{\partial f_4}{\partial x_1}&\frac{\partial f_4}{\partial x_2}&\frac{\partial f_4}{\partial x_3}&\frac{\partial f_4}{\partial x_4}\end{bmatrix}$$

The resulting process jacobian matrix is given below,

$${\mathbf{A}}_{k}=\left[\begin{array}{cccc}\frac{{a}_{11}}{{v}_{k}}& \frac{{a}_{12}}{{{v}_{k}}^{2}}-1& {a}_{13}& \frac{1}{{mv}_{k}}\\ {a}_{21}& \frac{{a}_{22}}{{v}_{k}}& -\frac{{a}_{22}}{{{v}_{k}}^{2}}{\dot{\psi }}_{k}& 0\\ 0& 0& 0& 0\\ 0& 0& 0& 0\end{array}\right]$$

where \({a}_{13}=-\frac{{a}_{11}}{{{v}_{k}}^{2}}{\beta }_{k}-\frac{{a}_{12}}{{{v}_{k}}^{3}}{\dot{\psi }}_{k}-\frac{1}{{{mv}_{k}}^{2}}{F}_{b}\)  

The final discritized and linearized model is given as,

$$\begin{bmatrix}\beta_{k+1}\\{\dot\psi}_{k+1}\\v_{k+1}\\F_{b_{k+1}}\end{bmatrix}=\begin{bmatrix}1&0&0&0\\0&1&0&0\\0&0&1&0\\0&0&0&1\end{bmatrix}\begin{bmatrix}\beta_k\\{\dot\psi}_k\\v_k\\F_{bk}\end{bmatrix}+T\underbrace{{}_s\begin{bmatrix}\frac{\alpha_{11}}{v_k}&\frac{\alpha_{12}}{v_k^2}-1&\alpha_{13}&\frac1{mv_k}\\\alpha_{21}&\frac{\alpha_{22}}{v_k}&\frac{\alpha_{22}}{v_k^2}{\dot\psi}_k&0\\0&0&0&0\\0&0&0&0\end{bmatrix}}_{A_k}\begin{bmatrix}\beta_k\\{\dot\psi}_k\\v_k\\F_{bk}\end{bmatrix}+\begin{bmatrix}\frac{b_1}{v_k}\\b_2\\0\\0\end{bmatrix}\delta_k$$
(7)

Two sensor measurements are used in the observer design, lateral acceleration and yaw rate.

The measured lateral acceleration with influence from road bank force is given by,

$${a}_{y}{meas}={a}_{y}+\frac{{F}_{b}}{m}$$
(8)

The lateral acceleration is related to the single track model states as,

$${a}_{y}=v\left(\dot{\beta }+\dot{\psi }\right)$$
(9)

Substituting (4) in (9), and then (9) in (8) yields,

$${a}_{y}{meas}={a}_{11}\beta +\frac{{a}_{12}}{v}\dot{\psi }+\frac{1}{mv}{F}_{b}+{b}_{1}\delta$$
(10)

The resulting linearized measurement model is given below,

$$\begin{array}{ll}{\mathbf{y}}_{k}=h\left({\mathbf{x}}_{k}\right)=\left[\begin{array}{c}{\dot{\psi }}_{k}\\ {a}_{y}{meas}_{k}\end{array}\right]\\ \ \ \ \ =\left[\begin{array}{cccc}0& 1& 0& 0\\ {a}_{11}& \frac{{a}_{12}}{{v}_{k}}& \frac{{a}_{12}\dot{\psi }}{{{v}_{k}}^{2}}& \frac{1}{m}\end{array}\right]\left[\begin{array}{c}{\beta }_{k}\\ {\dot{\psi }}_{k}\\ {v}_{k}\\ {F}_{bk}\end{array}\right]+\left[\begin{array}{c}0\\ {b}_{1}\end{array}\right]\delta\end{array}$$
(11)

The road bank force is estimated from the observer and then we obtain the road bank angle \(\theta\) by,

$$\theta ={sin}^{-1}\left(\frac{{F}_{b}}{mg}\right)$$
(12)

After discretizing and linearizing the model, it is now possible to implement EKF algorithm to estimate the side slip angle and yaw rate using the standard EKF equations.

Prediction:

$$\begin{array}{l}{\mathbf{A}}_{k}=\frac{\partial f}{\partial {\mathbf{x}}_{k-1/k-1}}\\{\widehat{\mathbf{x}}}_{k/k-1}=f\left({\widehat{\mathbf{x}}}_{k-1/k-1},{u}_{k}\right)\\{\mathbf{P}}_{k/k-1}={\mathbf{A}}_{k-1}{\mathbf{P}}_{k-1/k-1}{{\mathbf{A}}^{T}}_{k-1}+\mathbf{Q}\end{array}$$

Update:

$$\begin{array}{l}\mathbf{K}={\mathbf{P}}_{k/k-1}{{\mathbf{C}}^{T}}_{k}{\left({\mathbf{C}}_{k}{\mathbf{P}}_{k/k-1}{{\mathbf{C}}^{T}}_{k}+\mathbf{R}\right)}^{-1}\\{\widehat{\mathbf{x}}}_{k\left|k\right.}={\widehat{\mathbf{x}}}_{k\left|k-1\right.}+\mathbf{K}\left({\mathbf{y}}_{k}-h\left({\widehat{\mathbf{x}}}_{k/k-1}\right)\right)\\{\mathbf{P}}_{k/k}=\left(\mathbf{I}-{\mathbf{K}\mathbf{C}}_{k}\right){\mathbf{P}}_{k/k-1}\end{array}$$

where,

\(\mathbf{Q}=\left[\begin{array}{cccc}{{q}_{\beta }}^{2}& 0& 0& 0\\ 0& {{q}_{\dot{\psi }}}^{2}& 0& 0\\ 0& 0& {{q}_{v}}^{2}& 0\\ 0& 0& 0& {{q}_{Fb}}^{2}\end{array}\right]\) is the covariance of the state vector, which is a design diagonal matrix, calibrated by the designer to obtain the desired performance of the filter, and the diagonal elements in the matrix represent the variance of the corresponding states.

\(\mathbf{R}=\left[\begin{array}{cc}{{r}_{\dot{\psi }}}^{2}& 0\\ 0& {{r}_{{a}_{y}{\text{meas}}}}^{2}\end{array}\right]\) is the measurement covariance, which is a design diagonal matrix, calibrated by the designer to obtain the desired performance of the filter, where the diagonal elements in the matrix represent the variance of the corresponding measurements.

\({\mathbf{P}}_{k}\) is the error covariance matrix, which is typically set to the identity matrix. In this case, since we have a 4th order system, it is set to the the identity 4 × 4 matrix. \({\mathbf{A}}_{k}\) is the process Jacobian matrix as computed above. \({\mathbf{C}}_{k}=\left[\begin{array}{cccc}0& 1& 0& 0\\ {a}_{11}& \frac{{a}_{12}}{{v}_{k}}& \frac{{a}_{12}\dot{\psi }}{{{v}_{k}}^{2}}& \frac{1}{m}\end{array}\right]\) is the measurement Jacobian matrix, and \({u}_{k}=\delta\) is the control input. The only difference between linear KF and EKF is that in the EKF case the process Jacobian \({\mathbf{A}}_{k}\) and the measurement Jacobian \({\mathbf{C}}_{k}\) are updated at every time step, while they are constant in the KF case.

Figure 3. demonstrates the flowchart of the implemented observer.

Fig. 3
figure 3

Flowchart of the implemented observer

4 Experimental Results

The algorithm was validated on a test vehicle equipped with dSPACE AutoBox, and other sensors such as IMU steering angle sensor, and wheel speed sensor. The GPS/INS is installed in the vehicle to be used for the algorithm validation, but was not used in the algorithm itself. The values of the parameters of the test vehicle that was used in the experiment are listed in Table 1 below.

Table 1 Vehicle parameters

The state vector was initialized to zero,

$$\mathbf{x}={\left[{\beta }_{k}{\dot{\psi }}_{k}{v}_{k}{F}_{bk}\right]}^{\prime}=\left[\begin{array}{cccc}0& 0& 0& 0\end{array}\right]$$

The error covariance matrix \({\mathbf{P}}_{k}\) is usually initialized to the identity matrix,

$${\mathbf{P}}_{0}=\left[\begin{array}{cccc}1& 0& 0& 0\\ 0& 1& 0& 0\\ 0& 0& 1& 0\\ 0& 0& 0& 1\end{array}\right]$$

The \(\mathbf{Q}\) and \(\mathbf{R}\) matricies were calibrated as,

$$\begin{array}{cc}\mathbf{Q}=\left[\begin{array}{cccc}0.01& 0& 0& 0\\ 0& 0.001& 0& 0\\ 0& 0& 0.001& 0\\ 0& 0& 0& 100000\end{array}\right],&\mathbf{R}=\left[\begin{array}{cc}1& 0\\ 0& 100\end{array}\right]\end{array}$$

As can be seen from the process covariance matrix above, the variance term that corresponds to the road bank angle was chosen to be a very large value \({{q}_{Fb}}^{2}=100000\) because of the high uncertainty in the road bank angle, while the covariance terms that correspond to the vehicle states were chosen to small values becaue they have more certainty.

The road bank angle is validated by driving on roads with previously known bank angles, and in both curved and straight roads. For example, in Fig. 4, there are two sections of curved roads with bank angles, the first one is 13degrees and the second one is 19 degrees, and there is a straight section in between with very little bank angle. In this scenario, we started recording right before we entered the first bank, until we exited the second bank. As can be seen in Fig. 4(a), the estimator worked reasonably well in estimating the two large banks, and the little bank in the straight section, with smooth transitioning between the three different sections. Figure 4(b) shows the vehicle speed during the maneuver. The side slip angle and the yaw rate were validated with measurements from the GPS/INS system, as can be seen in Fig. 4(c), which shows the side slip angle estimate, and Fig. 4(d), which shows the yaw rate estimate.

Fig. 4
figure 4

a Estimated road bank angle. b Vehicle longitudinal speed during the maneuver. c Estimated side slip angle compared with the side slip angle from GPS/INS measurement d Estimated yaw rate compared with the yaw rate from GPS/INS measurement

Figure 5 demonstrates driving on a test track with 6 lanes road with different known banks. The bank starts in lane 6 with 38 degrees and then decreases gradually as we transition from lane 6 to lane 1. Figures 5(a), (b), (c), (d), (e), (f) show the bank angle estimation results on a 38 degrees, 18 degrees, 8 degrees, 2.5 degrees, 1.5 degrees, 1 degrees. It is worth mentioning that the speeds chosen reflect the speed limit for each lane but not necessarily the vehicle speed. We drove on all 6 lanes and took separate recording on each lane. As can be seen from the recorded data in Fig. 4, our road bank angle estimate started with about 38 degrees and decreased as expected as we transitioned to the lanes with less bank.

Fig. 5
figure 5

Driving on a 6 lanes road. a Lane 6, 38 degrees. b Lane 5, 18 degrees. c Lane 4, 8 degrees. d Lane 3, 2.5 degrees. e Lane 2, 1.5 degrees. f Lane 1, 1 degrees. The titles of all graphs indicate the lane number and the speed limit as indicated by the test track and not necessarily the speed of the test vehicle during the maneuver

5 Conclusion and Future Work

This paper developed a real-time observer for estimation of road bank angle and side slip angle using inexpensive on board vehicle sensors. The algorithm utilizes a combination of yaw rate and lateral acceleration measurements from IMU and a vehicle model that describes the vehicle lateral motion in terms of side slip angle and yaw rate. The developed algorithm was evaluated through experimental tests on a prototype vehicle on a test track with previously known bank angles. The results of the side slip angle and yaw rate angle were compared with the estimate from a GPS/INS system installed in the vehicle. The experimental results show that the algorithm provides estimates with reasonable accuracy for the vehicle side slip angel and road bank angle in various manauvers.

The limitation of this approach is that it does not work at very low speeds below 10 mps because at such speeds, there isn’t enough lateral forces to generate slip. To overcome this limitation, we are currently working on combining this model with a kinematic model. We switch to the Kinematic model only at the speed threshold mentioned above because kinematic models works only at very low speeds.