Skip to main content
  • Original Article
  • Open access
  • Published:

Rollover Prevention and Motion Planning for an Intelligent Heavy Truck

Abstract

It is very necessary for an intelligent heavy truck to have the ability to prevent rollover independently. However, it was rarely considered in intelligent vehicle motion planning. To improve rollover stability, a motion planning strategy with autonomous anti rollover ability for an intelligent heavy truck is put forward in this paper. Considering the influence of unsprung mass in the front axle and the rear axle and the body roll stiffness on vehicle rollover stability, a rollover dynamics model is built for the intelligent heavy truck. From the model, a novel rollover index is derived to evaluate vehicle rollover risk accurately, and a model predictive control algorithm is applicated to design the motion planning strategy for the intelligent heavy truck, which integrates the vehicle rollover stability, the artificial potential field for the obstacle avoidance, the path tracking and vehicle dynamics constrains. Then, the optimal path is obtained to meet the requirements that the intelligent heavy truck can avoid obstacles and drive stably without rollover. In addition, three typical scenarios are designed to numerically simulate the dynamic performance of the intelligent heavy truck. The results show that the proposed motion planning strategy can avoid collisions and improve vehicle rollover stability effectively even under the worst driving scenarios.

1 Introduction

1.1 Motivation

In the past few decades, the autonomous driving technology has rapidly developed. In the next 30 years, there will be more and more intelligent vehicles running on the public roads, which not only reflects national technical strength, but also helps to alleviate urban traffic congestion [1, 2]. Motion planning is a very important role for an intelligent vehicle. Proper motion planning algorithm can significantly reduce traffic accidents caused by tired driver or drunk driver [3]. Majority of the researchers focus on obstacle avoidance in motion planning. However, severe steering at high speed may cause vehicle rollover, especially for heavy trucks due to the long wheelbase, the large unsprung mass and the high center of gravity. In 2016, there were about 6.1 million traffic accidents in the United States. Among those crashes, vehicle rollover accidents account for only 2.0%, while rollover casualties account for 18.9% of traffic accident casualties, and most of them came from sport utility vehicles and heavy trucks [4]. Therefore, the research on motion planning to improve the autonomous anti rollover ability of intelligent heavy truck is very necessary.

1.2 Research Background

In recent years, many scholars have studied intelligent vehicle motion planning. The published classical motion planning algorithms including Dijkstra algorithm [5], A algorithm [6] and D algorithm [7], mainly applied the graph search approach to divide the environment map into a series of discrete grids then find the shortest path. However, the obtained shortest path based on the graph searching algorithm is discrete. It is hard to integrate with the dynamic characteristics of the vehicle. The samples-based approaches have attracted the attention of scholars, which randomly sampled the state space to find the connectivity then obtained the optimal path as quick as possible, such as Probabilistic Road Maps (PRM) [8] and Rapidly-exploring Random Trees (RRT) [9]. To solve the problem of path discontinuity, scholars optimized the existing trajectories based on interpolation curves and generated a new set of data using a previous set of nodes to obtain a smoother and more reasonable path, including the clothoid curve [10], the Bezier curve [11], and the polynomial curve [12]. The artificial potential field approach is a typical numerical optimization algorithm that constructs the gravitational and the repulsion fields to guide the intelligent vehicle to destination and avoid collision [13]. Ji et al. superimposed the obstacle exponential function and the road trigonometric function, constructed a 3D virtual potential field, generated the optimal collision avoidance trajectory, and used the multi constraint model predictive control (MPC) to track the collision avoidance trajectory [14,15,16]. With the continuous application of artificial intelligence technology, machine learning is now being used to make decisions on autonomous vehicles. David et al. improved the classical multi-agent reinforcement learning algorithm and used the neural network and the kernel smoothing technology to perform the approximate greedy operation on the unknown environment, which could generate multiple alternative paths [17]. Wolf et al. searched for various extreme conditions through reinforcement learning, learned driving behavior in simulation and trained the autopilot system to plan a safe driving path [18]. To sum up, the path planning algorithm included the local path planning and the global path planning, also known as motion planning. This paper focuses on the motion planning of the intelligent heavy truck after the global path planning data have been obtained.

The main idea to make anti-rollover path planning is to take a rollover index that describes the vehicle rollover risk into consideration as the constraint in the motion planning algorithm. The rollover index is used to describe and determine whether the vehicle has reached the critical rollover point. The ratio of center of gravity height to half of track width was defined as static stability factor (SSF) to detect the vehicle rollover risk [19]. Jin et al. improved the accuracy of SSF and proposed the dynamic stability factor (DSF) to predict the vehicle rollover tendency [20]. The lateral load transfer ratio (LTR) was the most commonly used in terms of vehicle rollover observations in published studies [21, 22]. In order to measure rollover tendency of the vehicle under special tripped conditions, Jin et al. developed a new rollover index [23], and derived an improved vehicle rollover index for the triaxle bus [24]. Imine et al. estimated the lateral acceleration, the yaw rate, and the roll angle to evaluate the vehicle rollover stability [25]. Time to rollover (TTR) was an efficient indicator for the rollover warning [26]. Zhu et al. proposed a TTR warning algorithm and regulated TTR online by a back-propagation neural network. Currently, some scholars have considered the lateral stability in motion planning process [27]. Li et al. used the roll plane model to obtain the rollover state of the vehicle, and combined it with the 3D occupancy grid to generate a safe path without rollover and collision [28]. Cheng et al. put forward a lateral stability coordinated collision avoidance control system (LSCACS) [29]. The LSCACS obtained the reference values of yaw angle and side deflection angle through the linear vehicle model, determined the working mode of the system by combining with Time to Collision (TTC), and finally obtained the corresponding tire force based on the MPC control. He assessed the risk related to collision and instability using the dynamic risk assessment model based on genetic algorithm and used the fifth order polynomial equation to generate the path without collision and with high lateral stability [30].

1.3 Contributions

Despite the large amount of research in path planning, there are few researches on the active anti-rolled-over motion planning algorithm. Therefore, a motion planning strategy considering autonomous anti rollover ability for an intelligent heavy truck based on V2V communications is proposed in this study. The main contributions are as follows:

  1. (1)

    A rollover dynamic model is built and a novel rollover index is defined for the intelligent heavy truck, by considering the influence of unsprung mass in the front axle and the rear axle and the body roll stiffness on vehicle rollover stability.

  2. (2)

    The motion planning strategy with active anti rollover ability based on model predictive control is proposed, which integrates the active rollover prevention, the obstacle avoidance and the path tracking with multiple dynamic constraints.

  3. (3)

    Three typical danger scenarios are designed to numerically simulate the performance of obstacle avoidance and the effect of active rollover prevention of the motion planning strategy.

1.4 Paper Organization

This paper is organized as follows. The framework of the intelligent heavy truck motion planning is introduced in Section 2. Then, a nonlinear-coupled rollover model is established, which considers longitudinal, lateral, yaw, and roll motions of unsprung and sprung masses of each axle in Section 3. In addition, the motion planning strategy with autonomous anti rollover ability is derived, which integrates the vehicle rollover index, the obstacle artificial potential field, and the MPC motion planner in Section 4. Three typical scenarios are designed to numerically simulate the dynamic performance of the intelligent heavy truck in Section 5. Finally, conclusions are summarized in Section 6.

2 Framework of the Intelligent Heavy Truck Motion Planning

The overall framework of the proposed motion planning strategy with autonomous anti rollover ability for the intelligent heavy truck is demonstrated in Figure 1. The framework includes motion planning, heavy truck dynamic model, state estimator, V2V communications, perception and global planning. The perception module detects and classifies the static obstacle and the road data, determines their location and provides their speed, direction and shape using various sensors including Lidar, Radar, camera, and GPS. The static obstacle and the road data are then sent to the global planning and motion planning modules. The motion planning and the global planning modules acquire the states of the obstacle vehicles through V2V communications. The global planning module combines the environment information and the vehicle state (such as vehicle speed, yaw angular speed, and lateral inclination) from the state estimator module to generate the global path. Then, the MPC based motion planning module controls the heavy truck to track the global path while avoiding collisions, complying with the road regulations and preventing the rollover. Finally, the decision of the ego-vehicle is broadcast to the obstacle vehicles via V2V communications.

Figure 1
figure 1

The framework of the intelligent heavy truck motion planning

This paper focuses on motion planning for heavy truck. It is assumed that the data of obstacle vehicles and the global path have been obtained from the perception module, V2V communications and the global planning module.

3 Rollover Model of the Intelligent Heavy Truck

After the global path planning data is obtained, an appropriate vehicle dynamic model needs to be built to conduct the motion planning, and the trajectory tracking control algorithm for the reference path should be designed to achieve the smooth running of the automated heavy truck. Due to the characteristics of large mass, high center of gravity and uneven load distribution, it is easy to rollover in the process of driving. Therefore, this paper considers the roll stability of heavy trucks while conducting path planning. To simplify the modeling process, some idealized assumptions are made for heavy trucks:

  1. 1.

    The pitch and the vertical motion of the vehicle are ignored.

  2. 2.

    The influence of side wind is ignored.

  3. 3.

    The effect of tire aligning torque is ignored.

  4. 4.

    Only the characteristics of the pure side-slip linear tire are considered, while the horizontal and the vertical coupling relationship of the tire is ignored.

  5. 5.

    Only front wheel steering is considered.

Taking the coupling between the front axle roll angle and the rear axle roll angle into consideration, an ideal torsion bar with fixed torsional stiffness and no mass is used to link the front and the rear sprung systems. Since the unsprung mass of heavy trucks is large, its influence on the roll motion cannot be ignored. Hence, a seven-degree-of-freedom dynamic model can be obtained, as shown in Figure 2.

Figure 2
figure 2

Dynamic rollover model for an intelligent heavy truck

As shown in Figure 2, the motion differential equation of the intelligent heavy vehicle can be derived as follows:

Longitudinal motion:

$$m\left( {\dot{u} - vr} \right) = F_{{{\text{XT}}}} - F_{{\text{r}}} ,$$
(1)

where, m is the intelligent heavy truck mass, u is the vehicle longitudinal speed, v represents the vehicle lateral velocity, r is the vehicle yaw rate, FxT denotes the longitudinal force, Fr is the wheel rolling resistance.

Lateral motion:

$$ma_{{\text{y}}} - m_{{{\text{sf}}}} h_{{\text{f}}} \ddot{\varphi }_{{{\text{sf}}}} - m_{{{\text{sr}}}} h_{{\text{r}}} \ddot{\varphi }_{{{\text{sr}}}} = 2F_{{{\text{Y1}}}} \cos \delta_{{\text{f}}} + 2F_{{{\text{Y2}}}} ,$$
(2)

where, ay represents the vehicle lateral acceleration, δf represents the front wheel steering angle, msf and msr denote the equivalent sprung masses in the front axle and the rear axle, respectively. hf and hr are the heights between the roll center and the sprung mass center in the front axle and the rear axle, respectively. φsf and φsr are the roll angles of the sprung masses in the front axle and the rear axle, respectively. FY1 and FY2 denote the tires lateral forces in the front axle and the rear axle, respectively.

Yaw motion:

$$I_{{\text{Z}}} \dot{r} = 2aF_{{{\text{Y1}}}} \cos \delta_{{\text{f}}} - 2bF_{{{\text{Y2}}}} ,$$
(3)

where, Iz is the vehicle yaw inertia, a and b are the longitudinal distances from the front axle and the rear axle to the vehicle CG, respectively.

The front sprung mass roll motion:

$$\begin{gathered} I_{{{\text{Xf}}}} \ddot{\varphi }_{{{\text{sf}}}} = m_{{{\text{sf}}}} h_{{\text{f}}} a_{{\text{y}}} + m_{{{\text{sf}}}} gh_{{\text{f}}} \varphi_{{{\text{sf}}}} - k_{{\text{f}}} \left( {\varphi_{{{\text{sf}}}} - \varphi_{{{\text{uf}}}} } \right) \hfill \\ - l_{{\text{f}}} \left( {\dot{\varphi }_{{{\text{sf}}}} - \dot{\varphi }_{{{\text{uf}}}} } \right) - k_{{\text{b}}} \left( {\varphi_{{{\text{sf}}}} - \varphi_{{{\text{sr}}}} } \right), \hfill \\ \end{gathered}$$
(4)

where, IXf denotes the front sprung mass roll inertia, g denotes the gravitational acceleration, kf and lf represent the equivalent roll stiffness coefficient and damping coefficient of the suspension in the front axle, φuf denotes the front unsprung masses roll angle, kb represents the vehicle body torsion stiffness coefficient.

The rear sprung mass roll motion:

$$\begin{gathered} I_{{{\text{Xr}}}} \ddot{\varphi }_{{{\text{sr}}}} = m_{{{\text{sr}}}} h_{{\text{r}}} a_{{\text{y}}} + m_{{{\text{sr}}}} gh_{{\text{r}}} \varphi_{{{\text{sr}}}} - k_{{\text{r}}} \left( {\varphi_{{{\text{sr}}}} - \varphi_{{{\text{ur}}}} } \right) \hfill \\ - l_{{\text{r}}} \left( {\dot{\varphi }_{{{\text{sr}}}} - \dot{\varphi }_{{{\text{ur}}}} } \right) - k_{{\text{b}}} \left( {\varphi_{{{\text{sr}}}} - \varphi_{{{\text{sf}}}} } \right), \hfill \\ \end{gathered}$$
(5)

where, IXr denotes the rear sprung mass roll inertia, kr and lr represent the equivalent roll stiffness coefficient and damping coefficient of the suspension in the rear axle, φur is the rear unsprung mass roll angle.

The front unsprung mass roll motion:

$$\begin{gathered} 2F_{{{\text{Y1}}}} h_{{{\text{cf}}}} + m_{{{\text{uf}}}} \left( {h_{{{\text{uf}}}} - h_{{{\text{cf}}}} } \right)a_{{\text{y}}} = - m_{{{\text{uf}}}} g\left( {h_{{{\text{uf}}}} - h_{{{\text{cf}}}} } \right)\varphi_{{{\text{uf}}}} \hfill \\ - k_{{\text{f}}} \left( {\varphi_{{{\text{sf}}}} - \varphi_{{{\text{uf}}}} } \right) - l_{{\text{f}}} \left( {\dot{\varphi }_{{{\text{sf}}}} - \dot{\varphi }_{{{\text{uf}}}} } \right){ + }k_{{{\text{uf}}}} \varphi_{{{\text{uf}}}} , \hfill \\ \end{gathered}$$
(6)

where, muf represents the equivalent unsprung mass in the front axle, hcf and huf are the heights of the roll center and the unsprung mass center in the front axle, respectively. kuf denotes the equivalent roll stiffness coefficient of the front unsprung mass.

The rear unsprung mass roll motion:

$$\begin{gathered} 2F_{{{\text{Y2}}}} h_{{{\text{cr}}}} + m_{{{\text{ur}}}} \left( {h_{{{\text{ur}}}} - h_{{{\text{cr}}}} } \right)a_{{\text{y}}} = - m_{{{\text{ur}}}} g\left( {h_{{{\text{ur}}}} - h_{{{\text{cr}}}} } \right)\varphi_{{{\text{ur}}}} \hfill \\ - k_{{\text{r}}} \left( {\varphi_{{{\text{sr}}}} - \varphi_{{{\text{ur}}}} } \right) - l_{{\text{r}}} \left( {\dot{\varphi }_{{{\text{sr}}}} - \dot{\varphi }_{{{\text{ur}}}} } \right){ + }k_{{{\text{ur}}}} \varphi_{{{\text{ur}}}} , \hfill \\ \end{gathered}$$
(7)

where, mur represents the equivalent unsprung mass in the rear axle; hcr and hur are the heights of the roll center and the center of the rear unsprung mass, respectively. kur is the equivalent roll stiffness coefficient of the rear unsprung mass.

The vehicle lateral acceleration is

$$a_{{\text{y}}} = \dot{v}{ + }ur.$$
(8)

The state of longitudinal and lateral motion of the intelligent heavy truck are

$$\dot{X} = u\cos \psi - v\sin \psi ,$$
(9)
$$\dot{Y} = u\sin \psi + v\cos \psi ,$$
(10)

where X denotes the vehicle longitudinal displacement, Y represents the vehicle lateral displacement, ψ denotes the vehicle heading angle.

The tires lateral forces depend on the front wheel side slip angle βf and the rear wheel side slip angle βr.

The front wheel side slip angle and the rear wheel side slip angle can be expressed as

$$\beta_{{\text{f}}} = \arctan \left( {\frac{{v{ + }ar}}{u}} \right) - \delta_{{\text{f}}} ,$$
(11)
$$\beta_{{\text{r}}} = \arctan \left( {\frac{v - br}{u}} \right).$$
(12)

Assuming that the vehicle yaw rate and the vehicle lateral velocity are small relative to the vehicle longitudinal speed, Eqs. (11)–(12) can be linearized as follows.

$$\beta_{{\text{f}}} = \left( {\frac{{v{ + }ar}}{u}} \right) - \delta_{{\text{f}}} ,$$
(13)
$$\beta_{{\text{r}}} = \frac{v - br}{u}.$$
(14)

To simplify the vehicle rollover system, the linear models of the tires lateral forces are used.

$$F_{Y1} = - K_{{\text{f}}} \beta_{{\text{f}}} ,$$
(15)
$$F_{Y2} = - K_{{\text{r}}} \beta_{{\text{r}}} ,$$
(16)

where, Kf and Kr represent the front wheel cornering stiffnesses and the rear wheel cornering stiffnesses.

4 Motion Planning Strategy of the Intelligent Heavy Truck

To improve vehicle rollover stability, as shown in Figure 1, the motion planning strategy of the intelligent heavy truck includes the rollover index, the obstacle artificial potential field, the MPC motion planner, and the path tracking with multiple dynamic constraints.

4.1 Rollover Index of the Intelligent Heavy Truck

As shown in Eq. (17), the most commonly used vehicle rollover index LTR can be expressed as

$$LTR = \frac{{F_{{\text{L}}} - F_{{\text{R}}} }}{{F_{{\text{L}}} + F_{{\text{R}}} }},$$
(17)

where, FL and FR are the left wheel vertical load and the right wheel vertical load. It is difficult to measure the wheel vertical loads in real time, especially in some emergency cases [31]. Therefore, a novel rollover index should be derived from the model of the intelligent heavy truck.

As shown in Figure 2, the difference between the front left vertical load FL1 and the front right vertical load FR1, and the difference between the rear left vertical load FL2 and the rear right vertical load FR2 can be expressed as follows.

$$\left\{ \begin{gathered} \left( {F_{{{\text{L1}}}} - F_{{{\text{R1}}}} } \right)T_{wf} /2 = k_{{\text{f}}} \left( {\varphi_{{{\text{sf}}}} - \varphi_{{{\text{uf}}}} } \right) + l_{{\text{f}}} \left( {\dot{\varphi }_{{{\text{sf}}}} - \dot{\varphi }_{{{\text{uf}}}} } \right), \hfill \\ \left( {F_{{{\text{L2}}}} - F_{{{\text{R2}}}} } \right)T_{wr} /2 = k_{{\text{r}}} \left( {\varphi_{{{\text{sr}}}} - \varphi_{{{\text{ur}}}} } \right) + l_{{\text{r}}} \left( {\dot{\varphi }_{{{\text{sr}}}} - \dot{\varphi }_{{{\text{ur}}}} } \right), \hfill \\ \end{gathered} \right.$$
(18)

where, Twf is the front track width, and Twr is the rear track width.

In addition, the sum of the left vertical load and the right vertical load is equal to the load weight. So,

$$\left\{ \begin{gathered} F_{{{\text{L1}}}} + F_{{{\text{R1}}}} = m_{{\text{f}}} g, \hfill \\ F_{{{\text{L2}}}} + F_{{{\text{R2}}}} = m_{{\text{r}}} g, \hfill \\ \end{gathered} \right.$$
(19)

where, mf and mr are the front axle mass and the rear axle mass.

Substituting Eqs. (4) and (5) into Eq. (18), the difference between the left vertical load and the right vertical load can be rewritten as follows.

$$\left\{ \begin{gathered} F_{{{\text{L1}}}} - F_{{{\text{R1}}}} = \frac{ - 2}{{T_{{{\text{wf}}}} }}\left[ \begin{gathered} I_{{{\text{Xf}}}} \ddot{\varphi }_{{{\text{sf}}}} - m_{{{\text{sf}}}} gh_{{\text{f}}} \varphi_{{{\text{sf}}}} \hfill \\ - m_{{{\text{sf}}}} h_{{\text{f}}} a_{{\text{y}}} + k_{{\text{b}}} \left( {\varphi_{{{\text{sf}}}} - \varphi_{{{\text{sr}}}} } \right) \hfill \\ \end{gathered} \right], \hfill \\ F_{{{\text{L2}}}} - F_{{{\text{R2}}}} = \frac{ - 2}{{T_{{{\text{wr}}}} }}\left[ \begin{gathered} I_{{{\text{Xr}}}} \ddot{\varphi }_{{{\text{sr}}}} - m_{{{\text{sr}}}} gh_{{\text{r}}} \varphi_{{{\text{sr}}}} \hfill \\ - m_{{{\text{sr}}}} h_{{\text{r}}} a_{{\text{y}}} + k_{b} \left( {\varphi_{sr} - \varphi_{{{\text{sf}}}} } \right) \hfill \\ \end{gathered} \right]. \hfill \\ \end{gathered} \right.$$
(20)

From Eqs. (17), (19), and (20), the front rollover index and the rear rollover index can be obtained,

$$\left\{ \begin{gathered} RI_{{\text{f}}} = \frac{{ - \frac{2}{{T_{{{\text{wf}}}} }}\left[ \begin{gathered} I_{{{\text{Xf}}}} \ddot{\varphi }_{{{\text{sf}}}} - m_{{{\text{sf}}}} gh_{{\text{f}}} \varphi_{{{\text{sf}}}} \hfill \\ - m_{{{\text{sf}}}} h_{{\text{f}}} a_{{\text{y}}} + k_{{\text{b}}} \left( {\varphi_{{{\text{sf}}}} - \varphi_{{{\text{sr}}}} } \right) \hfill \\ \end{gathered} \right]}}{{m_{{\text{f}}} g}}, \hfill \\ RI_{{\text{r}}} = \frac{{ - \frac{2}{{T_{{{\text{wr}}}} }}\left[ \begin{gathered} I_{{{\text{Xr}}}} \ddot{\varphi }_{{{\text{sr}}}} - m_{{{\text{sr}}}} gh_{{\text{r}}} \varphi_{{{\text{sr}}}} \hfill \\ - m_{{{\text{sr}}}} h_{{\text{r}}} a_{{\text{y}}} + k_{b} \left( {\varphi_{sr} - \varphi_{{{\text{sf}}}} } \right) \hfill \\ \end{gathered} \right]}}{{m_{{\text{r}}} g}}. \hfill \\ \end{gathered} \right.$$
(21)

To evaluate rollover risk of the intelligent heavy truck, a novel rollover index (NRI) is defined from Eq. (21).

$$NRI = \left\{ {\begin{array}{*{20}l} { - 1,\quad \left( {aRI_{{\text{f}}} + bRI_{{\text{r}}} } \right) \le - L,} \hfill \\ {\frac{{aRI_{{\text{f}}} + bRI_{{\text{r}}} }}{L}, - L < \left( {aRI_{{\text{f}}} + bRI_{{\text{r}}} } \right) < L,} \hfill \\ {1,\quad \;L \le \left( {aRI_{{\text{f}}} + bRI_{{\text{r}}} } \right),} \hfill \\ \end{array} } \right.$$
(22)

where, L is the wheelbase.

Compared with the problem that the LTR is difficult to measure in real-time, the state quantity in NRI can be obtained through the sensor to ensure real-time performance.

To verify the accuracy and the feasibility of the NRI in evaluating the rollover of the heavy truck, three cases and a “2A truck” model in TruckSim are used.

Fishhook is one of the worst untripped rollover maneuver. In this case, the amplitude of steering angle is set to five degrees. The results of the vehicle NRI and the vehicle LTR at different running speeds are illustrated in Figure 3.

Figure 3
figure 3

Comparison between LTR and NRI in Fishhook maneuver: (a) u = 55 km/h; (b) u = 65 km/h.

Figure 3 shows that the curves of LTR and NRI are highly consistent with each other. The peak value of the NRI is − 0.7857, and that of the LTR is − 0.7559, as shown in Figure 3a. Also, the error between the NRI and the LTR is less than 4%. In addition, when the vehicle rolls over, as shown in Figure 3b, NRI and LTR reach − 1 at the same time.

4.2 Obstacle’s Artificial Potential Field

The basic idea of the artificial potential field (APF) is to construct a field including the repulsion and the attractor poles. The exponential and the trigonometric functions are applied in this study, to define an APF that can accurately and comprehensively reflect the integration of vehicle and road in dangerous driving state according to the information of road structure parameters, traffic running conditions and the positions of the obstacles. The APF includes road markers or boundaries (PR), crossable area (PC), and non-crossable area (PNC), as shown in Eq. (23).

$$APF{ = }\sum\limits_{q} {P_{{R_{q} }} } + \sum\limits_{j} {P_{{C_{j} }} } + \sum\limits_{i} {P_{{NC_{i} }} ,}$$
(23)

where q, j, and i denote the indices of the road markers or boundaries, the crossable area, and the non-crossable area, respectively.

  1. (1)

    Non-crossable area means the obstacles that the vehicle must avoid, such as vehicles and pedestrians. In this paper, the potential field of the non-crossable area is defined as Ref. [32]:

    $$\left\{ \begin{gathered} P_{{NC_{i} }} (X,Y) = \frac{{a_{i} }}{{s_{i} (\frac{{\rm {d}X}}{{X_{{{\text{si}}}} }},\frac{{\rm {d}Y}}{{Y_{{{\text{si}}}} }})^{{b_{i} }} }}, \hfill \\ X_{{{\text{si}}}} = X_{0} + uT_{0} + \frac{{\Delta u_{{a_{i} }}^{2} }}{{2a_{{\text{n}}} }}, \hfill \\ Y_{{{\text{si}}}} = Y_{0} + (u\sin \theta + u_{oi} \sin \theta )T_{0} + \frac{{\Delta v_{{a_{i} }}^{2} }}{{2a_{{\text{n}}} }}, \hfill \\ \end{gathered} \right.$$
    (24)

    where ai and bi are the parameters of the PNC, an denote the vehicle comfortable acceleration, X0 is the minimum longitudinal distance, and Y0 is the minimum lateral distance, respectively, dX denotes the longitudinal distance from the ego vehicle to the obstacle, and dY denotes the lateral distance from the ego vehicle to the obstacle, T0 represents the safe time interval, θ is the heading angle of the ego vehicle toward the obstacle, Xsi denotes the safe longitudinal distance, and Ysi denotes the safe lateral distance, uoi represents the movement obstacle speed, Δuai is the longitudinal relative speed between the ego vehicle and the obstacle, and Δvai is the lateral relative velocity between the ego vehicle and the obstacle.

  2. (2)

    Crossable area is less dangerous aera. The potential field can be achieved by the safe distance sj between the obstacle and the ego vehicle.

    $$P_{{C_{j} }} (X,Y) = a_{j} \exp \left( { - b_{j} s_{j} \left( {\frac{{\rm{d}X}}{{X_{{{\text{si}}}} }},\frac{{\rm{d}Y}}{{Y_{{\text{si}}} }}} \right)} \right),$$
    (25)

    where aj and bj represent the parameters of PC.

  3. (3)

    Road markers or boundaries are also not allowed to be crossed by vehicle, except that vehicle actively change lanes. The quadratic form function is used to obtain the potential field of the road markers or boundaries as follows.

    $$P_{{R_{q} }} (X,Y) = \left\{ \begin{gathered} a_{q} \left( {s_{Rq} (X,Y) - D_{a} } \right)^{2} \begin{array}{*{20}c} {} & {s_{Rq} (X,Y) < D_{a} ,} \\ \end{array} \hfill \\ \begin{array}{*{20}c} 0 & {} & {} & {\begin{array}{*{20}c} {\begin{array}{*{20}c} {} & {} & {} \\ \end{array} } & {} & {s_{Rq} (X,Y) \ge D_{a} ,} \\ \end{array} } \\ \end{array} \hfill \\ \end{gathered} \right.$$
    (26)

    where aq denotes the intensity parameter of PR, sRq and Da represent the safe lateral distance and the permitted lateral distance from the ego vehicle to the road boundary, respectively.

An example of the potential field of the non-crossable area is shown in Figure 4a, and the compound potential field of PCj and PRq of the two-lane road is shown in Figure 4b.

Figure 4
figure 4

Examples of the potential field: (a) The non-crossable area; (b) The crossable area and road boundaries

4.3 MPC Motion Planner of the Intelligent Heavy Truck

MPC algorithm is used to realize the motion planning and trajectory tracking for the intelligent heavy truck. The cost function includes the trajectory tracking, the vehicle NRI, and the obstacle’s APF. This will enable the intelligent heavy truck to follow the road regulations and track the global path, prevent rollover, and avoid the obstacles. In addition, the dynamics of the intelligent heavy truck in the future can be predicted from the vehicle rollover model. Finally, the control outputs of FxT and δf can be obtained by rolling the optimization the cost function using the nonlinear optimal solver.

In order to simplify the calculation of MPC motion planner, it is necessary to linearize the rollover model of the intelligent heavy truck.

The state space model of the intelligent heavy truck can be achieved by sorting out the motion differential Eqs. (1)–(16).

$$\dot{\user2{x}} = {\varvec{f}}({\varvec{x}},{\varvec{u}}_{{\varvec{c}}} ),$$
(27)

where,

$${\varvec{x}} = \left[ {\begin{array}{*{20}c} u & v & r & X & Y & \psi & {\dot{\varphi }_{sf} } & {\dot{\varphi }_{sr} } & {\varphi_{sf} } & {\varphi_{sr} } & {\varphi_{uf} } & {\varphi_{ur} } \\ \end{array} } \right]^{\rm{T}} ,\;{\varvec{u}}_{{\varvec{c}}} = \left[ {\begin{array}{*{20}c} {F_{xT} } & {\delta_{f} } \\ \end{array} } \right]^{\rm{T}} ,\;{\varvec{y}} = \left[ {\begin{array}{*{20}c} u & v & r & Y & {\dot{\varphi }_{sf} } & {\dot{\varphi }_{sr} } & {\varphi_{sf} } & {\varphi_{sr} } \\ \end{array} } \right]^{\rm{T}} .$$

After linearizing Eq. (27), the linear state space model of the intelligent heavy truck can be obtained as follows.

$$\left\{ \begin{gathered} \dot{\user2{x}} = {\varvec{Ax}} + {\varvec{Bu}}_{{\varvec{c}}} , \hfill \\ {\varvec{y}} = \user2{Cx,} \hfill \\ {\varvec{A}} = \frac{{\partial {\varvec{f}}}}{{\partial {\varvec{x}}}}, \hfill \\ {\varvec{B}} = \frac{{\partial {\varvec{f}}}}{{\partial {\varvec{u}}_{{\varvec{c}}} }}, \hfill \\ \end{gathered} \right.$$
(28)

where, the expressions of matrices A and B are very complex and difficult to obtain, so they are calculated by numerical method.

$${\mathbf{C}} = \left[ {\begin{array}{*{20}c} 1 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 1 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 1 & 0 & 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 & 1 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 & 0 & 1 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 1 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 1 & 0 & 0 \\ \end{array} } \right].$$

According to the first order differential quotient method, the discrete state-space equation can be described as follows:

$$\left\{ \begin{gathered} {\varvec{x}}(k + 1) = {\varvec{A}}_{k} {\varvec{x}}(k) + {\varvec{B}}_{k} {\varvec{u}}_{{\varvec{c}}} (k), \hfill \\ {\varvec{y}}(k) = {\varvec{C}}_{k} {\varvec{x}}(k), \hfill \\ \end{gathered} \right.$$
(29)

where, \(A_{k} = E + t_{s} A,B_{k} = t_{s} B,C_{k} = t_{s} C\), E is the unit matrix with same matrix order as A, and ts =0.001 is discrete sampling time.

To design model predictive controller, setting \({\varvec{\chi}}(k) = \left[ {\begin{array}{*{20}c} {{\varvec{x}}(k)} & {{\varvec{u}}_{{\varvec{c}}} (k)} \\ \end{array} } \right]^{\rm{T}}\), the state-space equation of prediction model can be transformed into

$$\left\{\begin{gathered} {\varvec{\chi}}(k + 1) = \hat{{A}}_{k} {\varvec{\chi}}(k) + \hat{{B}}_{k} \Delta {\varvec{u}}_{{\varvec{ck},}} \hfill \\ {\varvec{y}}(k) = \hat{\user2{C}}_{k} {\varvec{\chi}}(k), \hfill\\ \end{gathered} \right.$$
(30)

where,

$$\hat{\user2{A}}_{k} = \left[ {\begin{array}{*{20}c} {{\varvec{A}}_{k} } & {{\varvec{B}}_{k} } \\ {0_{1 \times 12} } & {1_{1 \times 2} } \\ \end{array} } \right],\hat{\user2{B}}_{k} = \left[ {\begin{array}{*{20}c} {{\varvec{B}}_{k} } \\ {1_{1 \times 2} } \\ \end{array} } \right],\hat{\user2{C}}_{k} = \left[ {\begin{array}{*{20}c} {{\varvec{C}}_{k} } & 0 \\ \end{array} } \right].$$

Therefore, the output prediction equation is

$${\varvec{Y}}_{{\varvec{c}}} \left( k \right) = {\varvec{\psi}}\left( k \right){\varvec{\chi}}\left( k \right) + {{\varvec{\Theta}}}\left( k \right){{\varvec{\Delta}}}{\varvec{U}}_{{\varvec{c}}} \left( k \right)$$
(31)

where,

$$\begin{gathered} \hfill \\ {{\varvec{\Theta}}}\rm{(}k\rm{) = }\left[ {\begin{array}{*{20}c} {\hat{\user2{C}}_{k} \hat{\user2{B}}_{k} } & 0 & 0 & 0 \\ {\hat{\user2{C}}_{k} \hat{\user2{A}}_{k} \hat{\user2{B}}_{k} } & {\hat{\user2{C}}_{k} \hat{\user2{B}}_{k} } & 0 & 0 \\ \cdots & \cdots & \ddots & \cdots \\ {\hat{\user2{C}}_{k} \hat{\user2{A}}_{k}^{{C_{h} - 1}} \hat{\user2{B}}_{k} } & {\hat{\user2{C}}_{k} \hat{\user2{A}}_{k}^{{C_{h} - 2}} \hat{\user2{B}}_{k} } & \cdots & {\hat{\user2{C}}_{k} \hat{\user2{B}}_{k} } \\ {\hat{\user2{C}}_{k} \hat{\user2{A}}_{k}^{{C_{h} }} \hat{\user2{B}}_{k} } & {\hat{\user2{C}}_{k} \hat{\user2{A}}_{k}^{{C_{h} - 1}} \hat{\user2{B}}_{k} } & \cdots & {\hat{\user2{C}}_{k} \hat{\user2{A}}_{k} \hat{\user2{B}}_{k} } \\ \vdots & \vdots & \ddots & \vdots \\ {\hat{\user2{C}}_{k} \hat{\user2{A}}_{k}^{{P_{h} - 1}} \hat{\user2{B}}_{k} } & {\hat{\user2{C}}_{k} \hat{\user2{A}}_{k}^{{P_{h} - 2}} \hat{\user2{B}}_{k} } & \cdots & {\hat{\user2{C}}_{k} \hat{\user2{A}}_{k}^{{P_{h} - C_{h} - 1}} \hat{\user2{B}}_{k} } \\ \end{array} } \right], \hfill \\ \end{gathered}$$
$${{\varvec{\Delta}}}{\varvec{U}}_{{\varvec{c}}} (k) = \left[ {\begin{array}{*{20}c} {{{\varvec{\Delta}}}{\varvec{u}}_{{\varvec{c}}} (k)} & {{{\varvec{\Delta}}}{\varvec{u}}_{{\varvec{c}}} (k + 1)} & \cdots & {{{\varvec{\Delta}}}{\varvec{u}}_{{\varvec{c}}} (k + C_{h} )} \\ \end{array} } \right]^{\rm{T}} ,$$
$${\varvec{Y}}_{{\varvec{c}}} (k) = \left[ {\begin{array}{*{20}c} {{\varvec{y}}(k + 1)} \\ {{\varvec{y}}(k + 2)} \\ \cdots \\ {{\varvec{y}}(k + C_{h} )} \\ \cdots \\ {{\varvec{y}}(k + P_{h} )} \\ \end{array} } \right],\begin{array}{*{20}c} {} & {} \\ \end{array} {\varvec{\psi}}(k) = \left[ {\begin{array}{*{20}c} {\hat{\user2{C}}_{k} \hat{\user2{A}}_{k} } \\ {\hat{\user2{C}}_{k} \hat{\user2{A}}^{2}_{k} } \\ \cdots \\ {\hat{\user2{C}}_{k} \hat{\user2{A}}^{{C_{h} }}_{k} } \\ \cdots \\ {\hat{\user2{C}}_{k} \hat{\user2{A}}^{{P_{h} }}_{k} } \\ \end{array} } \right].$$

It is very necessary to constrain the vehicle kinematics and dynamics in the MPC motion planning of the intelligent heavy truck. Firstly, the control outputs FxT and δf need to meet the following vehicle dynamics constraints.

$$\left\{ \begin{gathered} F_{{{\text{xT}}}} \le F_{{{\text{xT\_max}}}} = \frac{{T_{\max } }}{{R_{{\text{w}}} }}, \hfill \\ \left| {\delta_{{\text{f}}} } \right| \le \delta_{{{\text{fmax}}}} , \hfill \\ \left| {\Delta \delta_{{\text{f}}} } \right| \le\Delta \delta_{{{\text{fmax}}}} , \hfill \\ \end{gathered} \right.$$
(32)

where, Tmax is the maximum driving torque, FxT_max is the maximum longitudinal force, Rw denotes the wheel radius, δfmax denotes the maximum front wheel steering angle, and Δδfmax is the maximum front wheel steering angle increment.

In addition, the tire longitudinal force and the tire lateral force shall meet the friction ellipse constraint [33]. For brevity, the details of the specific derivation of the friction ellipse will not be expanded here.

$$\left\{ \begin{gathered} \left( {\frac{{F_{{{\text{xT}}}} }}{{F_{{{\text{xT\_max}}}} }}} \right)^{2} + \left( {\frac{{F_{{{\text{Y1}}}} }}{{F_{{{\text{Y1\_max}}}} }}} \right)^{2} \le \mu^{2} , \hfill \\ \left( {\frac{{F_{{{\text{xT}}}} }}{{F_{{{\text{xT\_max}}}} }}} \right)^{2} + \left( {\frac{{F_{{{\text{Y2}}}} }}{{F_{{{\text{Y2\_max}}}} }}} \right)^{2} \le \mu^{2} , \hfill \\ \end{gathered} \right.$$
(33)

where, μ represents the road adhesion coefficient, FY1_max and FY2_max are the maximum lateral forces of the front tire and the rear tire, respectively.

Considering the vehicle dynamic constraints, the cost function of the MPC motion planner can be set up as follows.

$$\begin{gathered} J{ = }\sum\limits_{k = 1}^{{P_{h} }} {\left( \begin{gathered} \left\| {Y(t + k) - Y_{{{\text{ref}}}} (t + k)} \right\|_{{{\varvec{Q}}_{{1}} }}^{2} + \left\| {APF(t + k)} \right\|_{{{\varvec{Q}}_{{3}} }}^{2} \hfill \\ { + }\left\| {u(t + k) - u_{{{\text{ref}}}} (t + k)} \right\|_{{{\varvec{Q}}_{{2}} }}^{2} \hfill \\ { + }\left\| {NRI(t + k) - NRI_{{{\text{ref}}}} (t + k)} \right\|_{{{\varvec{Q}}_{{4}} }}^{2} \hfill \\ \end{gathered} \right)} \hfill \\ \begin{array}{*{20}c} {} & {} \\ \end{array} + \sum\limits_{k = 1}^{{C_{h} - 1}} {\left\| {\Delta {\varvec{u}}_{{\varvec{c}}} (t + k)} \right\|_{{\varvec{R}}}^{2} + \rho \varepsilon^{2} ,} \hfill \\ \end{gathered}$$
(34)

where, Ph and Ch are the prediction and the control horizons, respectively, Q1, Q2, Q3 and Q4 are the output state coefficient matrices, ρ denotes the weight coefficient, ε denotes the relaxation factor, R denotes the control weight coefficient matrix.

The designed lateral displacement Yref and the designed longitudinal speed uref can be obtained by global planning as shown in Figure 1. The designed NRIref is setting to 0.

In combination with the vehicle constraints shown in Eqs. (32) and (33), a series of control increments in the control time domain can be obtained by rolling the optimization the cost function using the nonlinear optimal solver Fmincon.

$${{\varvec{\Delta}}}{\varvec{U}}_{c}^{*} (k) = \left[ {\begin{array}{*{20}c} {{{\varvec{\Delta}}}{\varvec{u}}_{{\varvec{c}}}^{\user2{*}} (k)} & {{{\varvec{\Delta}}}{\varvec{u}}_{{\varvec{c}}}^{\user2{*}} (k + 1)} & \cdots & {{{\varvec{\Delta}}}{\varvec{u}}_{{\varvec{c}}}^{\user2{*}} (k + C_{h} )} \\ \end{array} } \right]^{\rm{T}} .$$
(35)

After obtaining the sequence of the control increments, the actual control input increment of the system can be calculated by the first element of the control sequence.

$${\varvec{u}}_{{\varvec{c}}} (k) = {\varvec{u}}_{{\varvec{c}}} (k - 1) + \Delta {\varvec{u}}_{{\varvec{c}}}^{\user2{*}} (k).$$
(36)

As the same way, the remaining input control increment of the system can be generated in turn by predicting the next cycle output according to the state information.

5 Numerical Cases Studies

Three numerical scenarios are designed to simulate the performance of the motion planning strategy of the intelligent heavy truck. Table 1 lists the main parameters of the intelligent heavy truck.

Table 1 Main parameters of the intelligent heavy truck

Scenario 1: Emergency obstacle avoidance. The intelligent heavy truck (ego vehicle) runs on Lane 1 at a constant speed of 80 km/h. Suddenly, a car (vehicle 1) directly in front of the ego-vehicle slows down to 40 km/h. As shown in Figure 5, the vehicle 2 moves on Lane 2 at the speed of 50 km/h, and the longitudinal distance in front of vehicle 1 (red car) is 10 m.

Figure 5
figure 5

Vehicles in Scenario 1

Figure 6 shows the vehicles’ trajectories in Scenario 1. The blue box, the red box, and the green box denote the intelligent heavy truck, the vehicle 1 and the vehicle 2, respectively. The red line and the green line represent the trajectory of the vehicle 1 and the vehicle 2, respectively. The blue curve and the pink curve are the trajectories of the ego vehicle with/without active anti rollover ability. When t=1 s, the ego-vehicle is still behind the vehicle 1. The ego vehicle had to change to Lane 2 in order not to collide with the vehicle 1. Also, during lane change, the ego vehicle does not collide with the vehicle 2, as shown in Figure 6 at t=2 s and t=2.5 s. When the ego vehicle overtakes the vehicle 1, it changes back to Lane 1. Thus, both the motion planning strategies with and without active anti rollover ability can effectively avoid obstacles.

Figure 6
figure 6

Vehicles’ trajectories in Scenario 1

As shown in Figure 7, the rollover stability and the output front wheel steering angle are illustrated for the intelligent heavy truck with and without active anti rollover ability. Figure 7a shows the NRI of the intelligent heavy truck. The NRI value varies between − 1 and 1, and the intelligent heavy truck is stable. However, the NRI value reaches − 1 at 2.8 s when the motion planning strategy without active anti rollover ability. That is, the intelligent heavy truck rolls over, although it avoids all obstacles. In addition, the output front wheel steering angle reaches the maximum steering angle limited by the constraint to avoid the obstacle when the vehicle without active anti rollover ability, as shown in Figure 7b. The motion planning strategy with active anti rollover ability outputs appropriate steering angle to avoid the obstacle and reduce the vehicle rollover risk.

Figure 7
figure 7

Rollover stability of the intelligent heavy truck in Scenario 1: (a) NRI; (b) The front wheel steering angle

As shown in Figure 8, the longitudinal dynamics of the intelligent heavy truck in Scenario 1 are drawn. The speed of the ego vehicle tends to slow down when it starts to turn. In order to ensure that the ego vehicle runs at the target speed, the motion planning algorithm responds to the appropriate longitudinal force in time. Since the motion planning strategy without active anti rollover ability outputs larger steering angle, the longitudinal speed reduces as shown in Figure 8a. Thus, the larger longitudinal force needs to be obtained to maintain the longitudinal speed as shown in Figure 8b. Therefore, the motion planning strategy with active anti rollover ability can maintain longitudinal stability and comfort of the intelligent heavy truck.

Figure 8
figure 8

Longitudinal dynamics of the intelligent heavy truck in Scenario 1: (a) Longitudinal speed; (b) Longitudinal force

Scenario 2: Obstacle avoidance on curved road. As shown in Figure 9, the ego vehicle is travelling on Lane 1 at an initial speed of 80 km/h, and the vehicle 1 is travelling on Lane 2 at a constant speed of 80 km/h. There is a fixed obstacle of 1 m in length and width in the curve part on Lane 1. The ego vehicle needs to make an emergency change to Lane 2, and reduce the speed in order not to collide with vehicle 1 on Lane 2.

Figure 9
figure 9

Vehicles and obstacle in Scenario 2

As shown in Figure 10, the blue box, the red box, and the green box denote the ego vehicle, the vehicle 1, and the fixed obstacle, respectively. The red curve is the trajectory of the vehicle 1. The blue curve and the pink curve are the trajectories of the ego vehicle with/without active anti rollover ability. When = 1 s, the ego vehicle has not yet detected the fixed obstacle and runs normally along lane 1. Then at = 3 s, the ego vehicle identifies the fixed obstacle, slows down and gradually moves to Lane 2. The vehicle successfully avoids the obstacle at = 4 s, and does not collide with the vehicle 1 during lane changing. The motion planning strategy without active anti rollover ability obtains the pink curve, which is more far away from the fixed obstacle. As can be seen, this path performs better at avoiding obstacles, but cannot guarantee the vehicle stability.

Figure 10
figure 10

Vehicles’ trajectories in Scenario 2

Figure 11 analyzes the rollover stability of the intelligent heavy truck in Scenario 2. Similar to Scenario 1, the proposed motion planning strategy with active anti rollover ability performs well in reducing the amplitude of NRI by about 0.2. The front wheel steering angle increases gradually, which is consistent with the actual driving condition. The front wheel steering angle output by the motion planning strategy with active anti rollover ability a slightly less than that without active anti rollover ability. From the results in Figure 11, it can be illustrated that the proposed strategy can avoid obstacles smoothly and reduce the vehicle rollover risk during cornering.

Figure 11
figure 11

Rollover stability of the intelligent heavy truck in Scenario 2: (a) NRI; (b) The front wheel steering angle

The longitudinal dynamics of the intelligent heavy truck in Scenario 2 is illustrated in Figure 12. In the first second, the vehicle has not detected the obstacle. Therefore, the longitudinal force is the driving force to keep the ego vehicle at a speed of 80 km/h. Then, to avoid collision with the obstacle and adjacent vehicle 1, the longitudinal force is the braking force that gradually increases and reduces the speed to 50 km/h. The ego vehicle speed is slightly less than that controlled by the motion planning without active anti rollover ability. The reduction of vehicle speed can also improve the vehicle rollover stability. This shows that the proposed strategy still puts up a good performance in longitudinal stability in Scenario 2.

Figure 12
figure 12

Longitudinal dynamics of the intelligent heavy truck in Scenario 2: (a) Longitudinal speed; (b) Longitudinal force

Scenario 3: Extreme turning condition. As shown in Figure 13, an extreme urgent scenario is designed to validate the performance of the motion planning with active anti rollover ability. The intelligent heavy truck runs on a two-way lane at a speed of 50 km/h. There are two large detours in this section lane. A fixed obstacle of 1 m in length and width suddenly appears on Lane 1 when the ego vehicle is 15 m away from the first curve. Similarly, another fixed obstacle with length and width of 1 m appears on Lane 1, when the ego vehicle is 15 m away from the second curve.

Figure 13
figure 13

Vehicle and obstacles in Scenario 3

As shown in Figure 14, the blue curve and the pink curve represent the vehicle trajectories controlled by the motion planning strategy with and without active anti rollover ability in Scenario 3. Two green boxes are the fixed obstacles. Both the blue curve and the pink curve indicate that the vehicle can successfully avoid the first fixed obstacle and pass the first detour safely. In addition, the motion planning strategy with active anti rollover ability can help the vehicle avoid the second fixed obstacle and pass the second detour safely. However, the pink curve disappears after the vehicle pass the first detour. That is, the vehicle rolls over and stop. Therefore, the motion planning strategy with active anti rollover ability can provide the vehicle safety under extreme turning condition.

Figure 14
figure 14

Vehicle’s trajectories in Scenario 3

Figure 15 shows that under extreme turning condition, the NRI value of the intelligent heavy truck controlled by the motion planning strategy without active anti rollover ability reaches − 1 at 7 s and then rolls over. However, when the vehicle travels according to the motion planning strategy with active anti rollover ability, although the absolute value of NRI of the vehicle is also large at 8 s, it is quickly adjusted and no rollover is occurred. The front wheel steering angle calculated by the motion planning strategy with active anti rollover ability is smaller than that without active anti rollover ability, as shown in Figure 15b. This also shows that the proposed motion planning strategy emphasizes on the vehicle lateral stability while ensuring safe avoidance of fixed obstacles.

Figure 15
figure 15

Rollover stability of the intelligent heavy truck in Scenario 3: (a) NRI; (b) The front wheel steering angle

Figure 16 illustrates the longitudinal dynamics of the intelligent heavy truck under extreme turning condition. Controlled by the motion planning strategy with active anti rollover ability, the vehicle longitudinal speed decreases slightly during passing the first detour. The output longitudinal force increases appropriately and keep the vehicle speed stable at the target speed of 50 km/h after the first detour. However, without active anti rollover ability, the motion planning algorithm leads vehicle to rollover.

Figure 16
figure 16

Longitudinal dynamics of the intelligent heavy truck in Scenario 3: (a) Longitudinal speed; (b) Longitudinal force

In conclusion, the simulation analysis of three dangerous scenarios verifies that the motion planning strategy with active anti rollover ability for the intelligent heavy truck can effectively avoid the moving vehicles and the fixed obstacles, and improve the vehicle longitudinal and lateral stability. Especially, it can prevent the vehicle rollover under some extreme driving conditions.

6 Conclusions

This paper proposes a motion planning strategy with active anti rollover ability based on model predictive control for the intelligent heavy truck. Considering the influence of unsprung mass in the front axle and the rear axle and the body roll stiffness on vehicle rollover stability, a rollover dynamic model is built and a novel rollover index is defined for the intelligent heavy truck. The motion states of the obstacles are obtained through the perception module and V2V communications. An MPC motion planner is designed, which integrates the active rollover prevention, the obstacle avoidance and the path tracking with multiple dynamic constraints. Numerically simulation results under some danger scenarios verify that the proposed motion planning strategy can effectively avoid the moving vehicles and the fixed obstacles, and prevent vehicle rollover.

References

  1. N González, J Pérez, V Milanés, et al. A review of motion planning techniques for automated vehicles. IEEE Transactions on Intelligent Transportation Systems, 2016, 17(4): 1135–1145.

    Article  Google Scholar 

  2. J Ni, J Hu, C Xiang. A review for design and dynamics control of unmanned ground vehicle. Proceedings of the Institution of Mechanical Engineers Part D Journal of Automobile Engineering, 2021, 235(4): 1084–1100.

    Article  Google Scholar 

  3. S Yang, Y Cao, Z Peng, et al. Distributed formation control of nonholonomic autonomous vehicle via RBF neural network. Mechanical Systems and Signal Processing, 2017, 87(1): 81–95.

    Article  Google Scholar 

  4. National Highway Traffic Safety Administration, Traffic safety facts 2016: A compilation of motor vehicle crash data from the fatality analysis reporting system and the general estimates system. US, Department of Transportation, Washington, DC, 2018: 70–77.

  5. A Bacha, C Bauman, R Faruque, et al. Odin: Team Victor Tango's entry in the DARPA urban challenge. Journal of Field Robotics, 2008, 25(8): 467–492.

    Article  Google Scholar 

  6. M Likhachev, D Ferguson. Planning long dynamically feasible maneuvers for autonomous vehicles. The International Journal of Robotics Research, 2009, 28(8): 933–945.

    Article  Google Scholar 

  7. A Stentz. Optimal and efficient path planning for partially–known environments. T Robotics and Automation, 1994 IEEE International Conference, 1994: 3310–3317.

  8. Y Kuwata, J Teo, G Fiore, et al. Real-time motion planning with applications to autonomous urban driving. IEEE Transactions on Control Systems Technology, 2009, 17(5): 1105–1118.

    Article  Google Scholar 

  9. S Karaman, E Frazzoli. Sampling-based algorithms for optimal motion planning. International Journal of Robotics Research, 2011, 30(7): 846–894.

    Article  Google Scholar 

  10. M Brezak, I Petrovic. Real-time approximation of clothoids with bounded error for path planning applications. IEEE Transactions on Robotics, 2014, 30(2): 507–515.

    Article  Google Scholar 

  11. J Rastelli, R Lattarulo. Dynamic trajectory generation using continuous–curvature algorithms for door to door assistance vehicles. 2014 IEEE Intelligent Vehicles Symposium (IV), 2014: 510–515.

    Google Scholar 

  12. P Petrov, F Nashashibi. Modeling and nonlinear adaptive control for autonomous vehicle overtaking. IEEE Transactions on Intelligent Transportation Systems, 2014, 15(4): 1643–1656.

    Article  Google Scholar 

  13. R Jing, K Mcisaac, R Patel. Modified Newton’s method applied to potential field–based navigation for mobile robots. IEEE Transactions on Robotics, 2006, 22(2): 384–391.

    Article  Google Scholar 

  14. J Ji, A Khajepour, W Melek, et al. Path planning and tracking for vehicle collision avoidance based on model predictive control with multiconstraints. IEEE Transactions on Vehicular Technology, 2017, 66(2): 952–964.

    Article  Google Scholar 

  15. Y Rasekhipour, A Khajepour, S Chen, et al. A potential field-based model predictive path-planning controller for autonomous road vehicles. IEEE Transactions on Intelligent Transportation Systems, 2017, 18(5): 1255–1267.

    Article  Google Scholar 

  16. H Wang, Y Huang, A Khajepour, et al. Crash mitigation in motion planning for autonomous vehicles. IEEE Transactions on Intelligent Transportation Systems, 2019, 20(9): 3313–3323.

    Article  Google Scholar 

  17. L David, Y Wen. Path planning of multi-agent systems in unknown environment with neural kernel smoothing and reinforcement learning. Neurocomputing, 2017, 233(4): 34–42.

    Google Scholar 

  18. P Wolf, C Hubschneider, M Weber, et al. Learning how to drive in a real world simulation with deep Q-networks. IEEE Intelligent Vehicles Symposium (IV), 2017: 244–250.

  19. R Huston, F Kelly. Another look at the static stability factor (SSF) in predicting vehicle rollover. International Journal of Crashworthiness, 2014, 19(6): 567–575.

    Article  Google Scholar 

  20. Z Jin, J Weng, H Hu. Rollover stability of a vehicle during critical driving manoeuvres. Proceedings of the Institution of Mechanical Engineers Part D: Journal of Automobile Engineering, 2007, 221(9): 1041–1049.

    Google Scholar 

  21. Y Zhang, A Khajepour, X Xie. Rollover prevention for sport utility vehicles using a pulsed active rear-steering strategy. Proceedings of the Institution of Mechanical Engineers Part D: Journal of Automobile Engineering, 2016, 230(9): 1239–1253.

    Google Scholar 

  22. W Zhao, L Ji, C Wang. H∞ control of integrated rollover prevention system based on improved lateral load transfer rate. Transactions of the Institute of Measurement and Control, 2019, 41(3): 859–874.

    Article  Google Scholar 

  23. Z Jin, L Zhang, J Zhang, et al. Stability and optimised H∞ control of tripped and untripped vehicle rollover. Vehicle System Dynamics, 2016, 54(10): 1405–1427.

    Article  Google Scholar 

  24. Z Jin, J Li, Y Huang, et al. Study on rollover index and stability for a triaxle bus. Chinese Journal of Mechanical Engineering, 2019, 32: 64.

    Article  Google Scholar 

  25. H Imine, M Djemaï. Switched control for reducing impact of vertical forces on road and heavy-vehicle rollover avoidance. IEEE Transactions on Vehicular Technology, 2015, 65(6): 4044–4052.

    Article  Google Scholar 

  26. X Zeng, G Li, D Song, et al. Rollover warning algorithm based on genetic algorithm-optimized BP neural network. Journal of South China University of Technology, 2017, 45(2): 30–38.

    Google Scholar 

  27. B Zhu, Q Piao, J Zhao, et al. Integrated chassis control for vehicle rollover prevention with neural network time-to-rollover warning metrics. Advances in Mechanical Engineering, 2016, 8(2): 1–13.

    Google Scholar 

  28. X Li, B Tang, J Ball, et al. Rollover-free path planning for off-road autonomous driving. Electronics, 2019, 8(6): 614–636.

    Article  Google Scholar 

  29. S Cheng, L Li, S Member. Longitudinal collision avoidance and lateral stability adaptive control system based on MPC of autonomous vehicles. IEEE Transactions on Intelligent Transportation Systems, 2019, 99(3): 1–10.

    Google Scholar 

  30. X He, Y Liu, C Lv, et al. Emergency steering control of autonomous vehicle for collision avoidance and stabilisation. Vehicle System Dynamics, 2019, 57(8): 1163–1187.

    Article  Google Scholar 

  31. M Arslan, M Sever. Vehicle stability enhancement and rollover prevention by a nonlinear predictive control method. Transactions of the Institute of Measurement and Control, 2019, 41(8): 2135–2149.

    Article  Google Scholar 

  32. J Schulman, J Ho, A Lee, et al. Finding locally optimal, collision–free trajectories with sequential convex optimization. Robotics: Science & Systems, 2013, 1–10.

  33. H Wang, Y Huang, A Khajepour. Cyber-Physical control for energy management of off–road vehicles with hybrid energy storage systems. IEEE/ASME Transactions on Mechatronics, 2018, 23(6): 2609–2618.

    Article  Google Scholar 

Download references

Acknowledgements

Not applicable.

Authors’ Information

Zhilin Jin, born in 1978, is currently an associate professor at Department of Vehicle Engineering, Nanjing University of Aeronautics and Astronautics, China. He received his PhD degree from Nanjing University of Aeronautics and Astronautics, China, in 2008. His research interests include vehicle system dynamics and control.

Jingxuan Li, born in 1997, is currently a graduate student at Nanjing University of Aeronautics & Astronautics, China.

Hong Wang, born in 1986, is currently a research associate professor at Tsinghua Intelligent Vehicle Design and Safety Research Institute, Tsinghua University, China.

Jun Li, born in 1958, is an Academician of Chinese Academy of Engineering. He is currently a professor at Tsinghua Intelligent Vehicle Design and Safety Research Institute, Tsinghua University, China.

Chaosheng Huang, born in 1972, is currently a research professor at Tsinghua Intelligent Vehicle Design and Safety Research Institute, Tsinghua University, China.

Funding

Supported by National Natural Science Foundation of China (Grant Nos. 51775269, U1964203, 52072215) and National Key R&D Program of China (Grant No. 2020YFB1600303).

Author information

Authors and Affiliations

Authors

Contributions

ZJ was in charge of the whole trial; JL wrote the manuscript; HW, JL and CH assisted with sampling and laboratory analyses. All authors read and approved the final manuscript.

Corresponding author

Correspondence to Hong Wang.

Ethics declarations

Competing Interests

The authors declare no competing financial interests.

Rights and permissions

Open Access This article is licensed under a Creative Commons Attribution 4.0 International License, which permits use, sharing, adaptation, distribution and reproduction in any medium or format, as long as you give appropriate credit to the original author(s) and the source, provide a link to the Creative Commons licence, and indicate if changes were made. The images or other third party material in this article are included in the article's Creative Commons licence, unless indicated otherwise in a credit line to the material. If material is not included in the article's Creative Commons licence and your intended use is not permitted by statutory regulation or exceeds the permitted use, you will need to obtain permission directly from the copyright holder. To view a copy of this licence, visit http://creativecommons.org/licenses/by/4.0/.

Reprints and permissions

About this article

Check for updates. Verify currency and authenticity via CrossMark

Cite this article

Jin, Z., Li, J., Wang, H. et al. Rollover Prevention and Motion Planning for an Intelligent Heavy Truck. Chin. J. Mech. Eng. 34, 87 (2021). https://doi.org/10.1186/s10033-021-00605-z

Download citation

  • Received:

  • Revised:

  • Accepted:

  • Published:

  • DOI: https://doi.org/10.1186/s10033-021-00605-z

Keywords