Skip to main content

TECHNOLOGY AND CODE article

Front. Robot. AI, 21 February 2023
Sec. Robotic Control Systems
Volume 10 - 2023 | https://doi.org/10.3389/frobt.2023.1120658

Research on automatic emergency steering collision avoidance and stability control of intelligent driving vehicle

www.frontiersin.orgZhaoyong Liu1,2 www.frontiersin.orgGaobo Wen1 www.frontiersin.orgWudong Liu1 www.frontiersin.orgTanXiaoqiang Tan1 www.frontiersin.orgGuangqiang Wu1*
  • 1School of Automotive Studies, Tongji University, Shanghai, China
  • 2Global Technology Co., Ltd, Nantong, China

In view of the need for emergency steering to avoid collision when the vehicle is in a dangerous scene, and the stability control of the vehicle during collision avoidance. This paper proposes a planning and control framework. A path planner considering the kinematics and dynamics of the vehicle system is used to formulate the safe driving path under emergency conditions. LQR lateral control algorithm is designed to calculate the output steering wheel angle. On this basis, adaptive MPC control algorithm and four-wheel braking force distribution control algorithm are designed to achieve coordinated control of vehicle driving stability and collision avoidance safety. The simulation results show that the proposed algorithm can complete the steering collision avoidance task quickly and stably.

Introduction

The Advanced Driver Assistance Systems (ADAS) are effective in reducing crashes. Most ADAS systems have one thing in common, that is, they all affect the longitudinal control of the vehicle to avoid the collision (Borrello et al., 2020; Rabhi et al., 2021; Zha et al., 2021; Hang et al., 2022; Wu et al., 2023).

Although, there are certain situations where a collision cannot be avoided by braking but only by steering operations. However, lots of studies show that in the case of an impending rear-end collision, many drivers tend to only brake rather than try to avoid obstacles by steering (Schieben et al., 2014). There are different reasons for this behavior. Firstly, it is an instinctive reaction to stop in order to reduce the impact of an impending collision. Secondly, steering is more complex than braking, so it requires the driver to have a higher awareness of the situation and a higher driving ability. Therefore, Automatic Emergency Steering System (AES) is of great significance.

For vehicle trajectory planning, Yang proposed a dynamic planning method for vehicle collaborative trajectory planning under the scenario of forced lane change, which aims to provide suggested lane change distance and reference trajectory for each autonomous vehicle in a coordinated manner (Yang et al., 2022). A dynamic programming way is established to determine the suggested distance of all vehicles and the non-convex quadratic constraint is applied to characterize the trajectory determination problem. Considering driver comfort and collision risk, Li et al. (2022) proposed a human-like motion planning strategy based on probabilistic prediction under dynamic environment. They realized path generation based on quintic polynomials, and optimized the target trajectory by using cost functions with four indexes including safety, consistency, smoothness and distance from local path to global path. Cheng et al. (2022) proposed a deep reinforcement learning method based on time difference to solve the longitudinal trajectory planning of autonomous vehicles at signal-controlled intersections. Xiao et al. (2021) [10] proposed the control barrier function method for critical safety control and developed a real-time control framework that combines the optimal trajectory generated with the computational efficiency method that provides safety assurance.

Vehicle collision risk assessment is the key to trigger AES. For vehicle risk assessment, Li et al., 2021 proposed a multi-scene collision avoidance decision algorithm for autonomous vehicles, and used the situation assessment module based on conditional random field to assess the risk level of the surrounding traffic participants. Based on the situation assessment module, collision avoidance strategies with driving style preferences (such as aggressive or conservative) are proposed to meet the needs of different drivers. Cui et al. (2021) proposed a layered framework of manned or autonomous vehicles for collision avoidance in emergency situations. They adopted finite-state machine (FSM) technology to determine appropriate strategies for collision avoidance, and established a collision risk model, taking into account vehicle risks around overlapping areas, road attachment risks and vehicle stability performance. Gilbert et al. (2021) proposed a decision-making system that selects the lightest collision when vehicles are confronted with inevitable collisions on the highway. They applied the multi-attribute decision-making method to judge the severity of the collision. For the autonomous lane change decision of trucks, Chen et al. (2020) proposed a lane change decision model based on support vector machine. Ren and Wu, 2020 proposed a fusion architecture of decision planning under dynamic Environment And Used Back Propagation Neural Network (BPNN) to predict the lane change of vehicles around the block.

The AES control layer will track the trajectory planned by the decision layer. For the vehicle trajectory tracking, Ge et al., 2022 rely on the precise model for the traditional MPC. When the autonomous vehicle encounters external interference and perturbation, the steady-state non-offset tracking cannot be realized, and the MPC solver is biased to solve the coupling control problem. Li et al. (2021) studied that under extreme driving conditions, the coupling between the longitudinal and transverse motion of the vehicle becomes significant due to the highly non-linear force of the tire, which affects the stability of the vehicle. They proposed a model prediction controller of electric vehicle driven by four-wheel independent motor, in which changes in the longitudinal velocity are regarded as interference in the vehicle dynamics model. Then, the additional torque generated by the model-based controller with the multi-objective design is considered for balance. Tork et al. (2021) proposed an independent model control based on neural network for path tracking control. The control scheme utilized the input of steering Angle and torque to realize cooperative control of transverse and longitudinal motion.

In summary, collision avoidance and stabilization are the two critical issues when an autonomous vehicle in an emergency situation, which usually occurs in a short time and requires large actuator inputs, as well as a highly non-linear response. Real-time vehicle decision-making, planning and control plays an important role in avoiding collisions while stabilizing autonomous vehicles in extreme scenarios. Liu et al. (2017) proposed a method to establish the stability criterion of vehicle yaw based on the phase plane method of sideslip-yaw rate, which solved the problem of judging the type of vehicle stability region under different driving conditions, and provided a theoretical basis for the intervention algorithm of stability control system. Zhang et al. (2017) considered the influence of tire slip and actuator torque saturation on driving and braking, and designed a dynamic controller to overcome integral saturation by using a conditional integrator to ensure accurate tracking of the required signals under the influence of tire force and actuator constraints. Vehicle state and parameter estimation is an important part of vehicle dynamic control. Liu et al. (2021) proposed a new estimation method of vehicle side-slip angle based on kinematic model, which integrated the information of Global Navigation Satellite System (GNSS) and inertial Measurement Unit (IMU). Xia et al. (2018) proposed a method to estimate the attitude and lateral velocity of an autonomous vehicle with the assistance of vehicle dynamics using a six-degree-of-freedom IMU. Liu et al. (2018) proposed a method based on kinematics model that integrates intelligent vehicle sensors to estimate sideslip angle, aiming at the problem that the non-linear characteristics and parameter uncertainties of vehicles make it difficult for the method based on dynamic model to estimate the sideslip angle of vehicles under harsh working conditions. Xiong et al. (2020) proposed a new automatic vehicle sideslip angle and attitude estimation method based on IMU for low sampling rate GNSS speed and position parallel adaptive Kalman filters.

The existing steering collision avoidance system often only considers the safety risk of collision avoidance, but does not consider the impact of dynamic factors on stability. At the same time, stability has a certain impact on tracking control accuracy, which should also be considered. Therefore, the contribution of this paper is to propose a real-time emergency steering collision avoidance and stability control method, and design a simulation experiment based on the influence of stability control on tracking accuracy and other factors.

As shown in Figure 1, the lateral path planning and path tracking control considering motion stability designed in this paper are parts of the coordinated control architecture of vehicle driving stability and collision avoidance safety, which can realize automatic collision avoidance control and ensure the vehicle’s security and stability. Based on perception and state estimation information, the framework judges driving safety and collision risk and makes decisions based on TTC (time to collision), and uses dynamic programming and quadratic programming methods to plan paths and determine collision-free paths. Then, according to the characteristics of stability control in emergency collision avoidance scenarios, an adaptive MPC control algorithm is designed. Finally, the obtained steering wheel angle and four-wheel braking force are applied to the actual vehicle.

FIGURE 1
www.frontiersin.org

FIGURE 1. Coordinated control for vehicle driving stability and collision avoidance safety.

Vehicle dynamics model

3-DOF vehicle dynamics model

We rationally simplified the vehicle model (Wu G. 2021) to obtain a three-degree-of-freedom(3-DOF) vehicle dynamics model, as shown in Figure 2, which mainly includes vehicle longitudinal, lateral and yaw motions, where δf is the front wheel angle, and FXi is the wheel braking force, FYi is the wheel lateral force, vx is the longitudinal speed, vy is the lateral speed, v is the speed of the vehicle, β is the sideslip angle, lf and lr are the distance of the center of mass and the front and rear axles, ls is the wheelbase, βf is the sideslip angle of the front wheel, Td is the sum of the yaw moment of the vehicle, r is the yaw rate of the vehicle.

FIGURE 2
www.frontiersin.org

FIGURE 2. 3-DOF vehicle dynamics model.

The differential equations of motion of the vehicle:

Fxi=mv˙xr×vyFyi=mv˙y+r×vxlfFy1+Fy2lrFy3+Fy4+lsFx1+Fx3lsFx2+Fx4=Td(1)

So far, the establishment of the 3-DOF model of the vehicle considering the lateral, longitudinal and yaw motions has been completed, and this model will be used to describe the basic characteristics of the vehicle during motion.

Linear tire model

In the case of a small vehicle front wheel angle, the relationship between the wheel lateral force and the sideslip angle of this wheel can be approximately regarded as a linear relationship (Wu G. 2021), thus:

FYi=kfβfi=1,2FYi=krβri=3,4(2)

Where kf and kr are the cornering stiffnesses of the front and rear axles, respectively. Front and rear wheel sideslip angles, vehicle sideslip angle and their derivatives are:

βf=β+lfrvxδfβr=βlrrvx(3)
β=vyvxβ˙=vy˙vxvx˙vyvx2(4)

Collision avoidance trajectory planning

The goal of trajectory planning is to generate a smooth enough curve to change the position of the vehicle under the premise of ensuring the safety of the vehicle. The smoothness is to ensure that the vehicle can track along the trajectory. The trajectory planning module will receive the environment information including vehicle location information and road information. A planned trajectory is transmitted to the vehicle motion control module as shown in Figure 3.

FIGURE 3
www.frontiersin.org

FIGURE 3. Trajectory planning during the steering.

Usually trajectory planning can be decomposed into speed planning and path planning. Since the change of speed is not considered in the planning process of steering collision avoidance, we assume that the longitudinal speed is constant in the planning process, and only the path planning is designed here.

Path planning

Using numerical methods, the path planning problem in discrete space can be abstracted as a quadratic programming problem, and the construction of this problem mainly includes two parts: the design cost function and the determination of the constraints of the problem. In designing the cost function, we need to consider the requirements of smoothness, not deviating from the road centerline and being away from obstacles. At the same time, in order to accelerate the solution, we first use dynamic programming to open up feasible space and therefore determine the constraints of the planning problem. After the problem is constructed, we use the iterative method to solve the quadratic programming problem.

The cost function of path planning can be divided into smoothing cost, reference line cost and obstacle cost. The road is discretized along the centerline and its perpendicular direction, x is the coordinate of the road centerline, and y is the coordinate of the point which is perpendicular to the road.

The smoothing cost Cpsmooth is divided into three parts, Wpsmooth1, Wpsmooth3, and Wpsmooth3, and their meanings correspond to the cost weights generated by the first, second, and third derivatives of the path:

Cpsmooth=Wpsmooth1yTy,+Wpsmooth2yTy+Wpsmooth3yTy(5)

The reference line cost is Cpref, and Wpref represents the corresponding weight:

Cpref=WprefyTy(6)

The obstacle cost is Cpcollision, Wpcollision represents the corresponding weight, and d represents the distance between the obstacle and the vehicle, where Wpcollision is a rather large value.

Cpcollision=0,ifd41000d,if3<d<4Wpcollision,ifd3(7)

Combining the above three formulas, the total planning cost Cpnode of each discrete point can be obtained, and its value is equal to the sum of the above three costs:

Cpnode=Cpsmooth+Cpref+Cpcollision(8)

The planned trajectory needs that the curvature is continuous. Δx is the sampling interval in the direction of the road centerline, yi is the first derivative of y to x at the i-th sampling point, yi is the second derivative of y to x at the i-th sampling point:

yi+1=yi+yiΔx+12yiΔx2+12yi+1yiΔxΔx2(9)

The solution of the planning is first to obtain the initial solution by dynamic programming, and then to obtain the final result by secondary programming, as shown in Figure 4. In order to speed up the calculation of the quadratic programming problem, the result of the dynamic programming is regarded as a rough solution and a feasible space is opened up. ymaxj, yminj is the maximum and minimum value of the feasible space, yminj,ymaxj is the value range of the path restricted by the road, y_obs is the position corresponding to the obstacle car, width/2 is the width of the obstacle car:

ymaxj=minymaxj,y_obswidth/2,ifydp_path>y_obsyminj=maxyminj,y_obs+width/2,others(10)

FIGURE 4
www.frontiersin.org

FIGURE 4. Path planning feasible space(DP).

After a lot of tuning, the parameters of the planning algorithm are finally selected Wpsmooth1=15;Wpsmooth2=20000;Wpsmooth3=5000; Wpref=15.

Quadratic programming problem solving

The advantage of Dynamic Programming (DP) is to decompose each column of the discrete space into a sub-problem and solve the optimal path from the last column through the inverse method. On the basis of discretization of the solution space, the initial path can be calculated by using dynamic programming. According to this path, a preliminary decision can be made on the path planning problem to reduce the search range of the quadratic feasible space, as shown in Figure 4. The advantage of the iterative method for solving quadratic programming problems is that it can balance the solution time and effect. This article does not focus on this aspect, so directly call the quadratic planner solution function in MATLAB.

Control strategy of collision avoidance system

In this paper, a path-following control system considering motion stability is proposed. Its purpose is to judge the risk of collision when an obstacle appears in front of the vehicle, and automatically implement emergency collision avoidance with the stability of the vehicle body, as shown in Figure 5. The structure of the system can be mainly divided into three parts: TTC risk assessment, LQR lateral control and adaptive Model Predictive Control (MPC) stability control.

FIGURE 5
www.frontiersin.org

FIGURE 5. Vehicle emergency steering and collision avoidance stability control.

First, according to the collision risk assessment module, the collision time TTC is calculated according to the state of the vehicle and the environment perception information to judge the safety of the current vehicle. TTC refers to the time it would take for a collision to occur at the prevailing speeds, distances, and trajectories associated with the driver’s vehicle and the closest lead vehicle. TTC can be kinematically defined as the range between a following and lead vehicle divided by the relative velocity between these vehicles. Hence, TTC provides a measure of crash risk or the time before impact if prevailing conditions continue (Coelingh et al., 2010; Han et al., 2014). We have carried out related research in this part, but it is not the focus of this article. Considering the complex and changeable traffic conditions, as well as the possible instability of the vehicle caused by the large action of the actuator, this paper designs an adaptive MPC module to control the yaw moment of the vehicle to ensure the stability of the vehicle. The module judges whether to intervene. In addition, the linear quadratic regulator (LQR) controller is proposed in this paper to calculate the output signal steering angle δ according to the lateral error eh and heading angle error ey, so that the vehicle can always track the road centerline. Finally, in terms of braking force control and distribution, the braking force distribution and control module will calculate the braking forces FX1FX2FX3FX4 according to the expected deceleration and the expected additional yaw moment of the vehicle, and From this, the braking pressures PX1PX2PX3PX4 of each wheel cylinder are further obtained.

LQR lateral control

The main purpose of lateral control is to control the lateral error within a certain range. As a result we can get a better track of the desired path and the heading angle of the vehicle. The content of this section is mainly based on the LQR to design the controller to track path. The state variables of the control system are four parameters, including: lateral error ey, rate of change of lateral error ey˙, and heading angle error eh, the rate of change of heading angle error eh˙. The following formula is the state space equation of the system:

ey˙ëyeh˙ëh=010001mu(kf+kr1mkf+kr1mulfkflrkr000101Izvxlfkflrkr1Izlfkflrkr1Izvxlf2kf+lr2kreyey˙eheh˙+0kfm0akfIzδf+01mvxakfbkrvx01Izvxa2kf+b2krδf˙(11)

Where:

A=010001mvx(kf+kr1mkf+kr1mvxlfkflrkr000101Izvxlfkflrkr1Izlfkflrkr1Izvxlf2kf+lr2kr,B=0kfm0akfIz,C=0akfbkrmvxδf0a2kf+b2krIzvx(12)

Eq.11 can be expressed as:

err˙=Aerr+Bu+Cθr˙(13)

Error:

err=eyey˙eheh˙T(14)

The control quantity is δf.

From the above state equation, we can get the objective function and corresponding constraints of the LQR controller:

MinJ=12t0tf(errtTQerr(t)+utTRu(t)dts.t.err˙=Aerrt+Bu(15)

Where t0,tf is the time domain, Q and R represent the weighted matrix of state and control quantity.

The optimal solution of this problem satisfies the following:

J*=errtTPerrt(16)

The expression of P is:

P˙=PtAt+ATtPtPtBtR1tBTtPt+Qt(17)

The LQR controller is:

uk=KtXt(18)

Where K=R1tBTtPt represents the controller gain.

Adaptive model predictive control stability control module

In order to trade off the calculation efficiency and calculation accuracy, we assume that the longitudinal velocity vx in the Formula. 1 of the vehicle dynamics model remains unchanged. At this time, the three-degree-of-freedom model of the vehicle is simplified to two-degree-of-freedom. At the same time, it is brought into the Formula. 4, where the longitudinal velocity vx is a time-varying model parameter, and the sideslip angle and the yaw rate are taken as the state quantities, which can be finally simplified to obtain the following state space equation:

r˙β˙=lf2kf+lr2krvxIzlfkflrkrIzkflfkrlrmvx21kf+krmvxvx˙vxrβ+1Iz0Td+lfkfIzkfmuδf(19)

Where select x=rβT as the state quantity, and u=Td as the control quantity.

Eq. 9 will calculate the reference values of the vehicle’s yaw rate and sideslip angle. The deviation value is used as the index of vehicle lateral stability, and the larger the value, the greater the risk of lateral instability of the vehicle.

rref=vx/lf+lr1+Kvx2δfβref=lr+mlfvx2/krlf+kflrlf+lr1+Kvx2K=mlf+lr2lfkrlrkf(20)

rref, βref are the reference yaw rate and sideslip angle, respectively, and K is the stability factor.

MPC is a feedback control strategy that discretizes the vehicle dynamics equation, and sets the sampling time as Ts=5×104s. For time k, there is the following discrete equation:

xk+1=Axk+Buuk+Bddkyk=Cxk+Duk(21)

Where,

A=TsAc+I,Bu=BcuTs,Bd=BcdTs,C=Cc,D=Dc

xk,uk,yk represent the state, control input and output of the system at time k, respectively. Assuming that the prediction time domain is ps, and the control time domain is ms, the control quantity will not change when the time exceeds the control time domain. Then the input and output predicted by time k are:

ypk+1|k,ypk+2|k,...,ypk+ps|k(22)
uk|k,uk+1|k,...,uk+ps1|k(23)

The control goal is to track the target and reduce the tracking error, that is,

rk+1,rk+2,...,rk+ps(24)

At the same time, the control constraints and output constraints of the system are set. Finally the optimization goal function that can characterize the control performance of the system is proposed. It needs to consider the cost of the expected tracking error and some other performances, such as the control action as small as possible. The objective function is:

Jyk,Uk=i=1psΓyrk+iypk+i|k2+i=1msΓuuk+i|kuk+i1|k2(25)

Γy is the weight of the output quantity, and Γy u is the weight of the control quantity increment. For time k, the open-loop optimization problem is transformed into solving minJxk,Uk,ms,ps for the control variable U.

In order to improve the calculation efficiency, the longitudinal velocity vx is assumed to be constant when calculating the state space equation, but in the process of emergency collision avoidance, its longitudinal velocity vx is a time variable. At this time, the internal model of MPC will also change with time, so an adaptive MPC solution method is proposed. The longitudinal velocity and longitudinal acceleration output by the system are fed back to the MPC controller to update the internal model of the controller, which is beneficial to improve controller performance.

After a large number of parameter tuning and system identification, the system can maintain the best performance as much as possible, and the corresponding parameters of the adaptive MPC controller are selected: prediction time domain ps = 10, control time domain ms = 5, and add hard constraints to the control input, Take umin=4000Nm, umax=4000Nm, Δumax=±1000Nm, Γu=0.02, Γy=12.

So far, the parameter setting of the adaptive MPC controller is completed, and the optimal additional yaw moment ΔM can be calculated to avoid vehicle instability.

Vehicle tire braking force distribution strategy

The additional yaw moment Td required by the vehicle has been obtained from the MPC controller as shown in Figure 6:

Td=i=141iFxiLi(26)

FIGURE 6
www.frontiersin.org

FIGURE 6. Four-wheel braking force distribution.

Fri,Ffi are the longitudinal forces of the front and rear tires, dri,dfi are the lateral distances from the front and rear tires to the center of gravity of the vehicle. I represents the left or right side of the vehicle.

At present, the braking force distribution schemes for active braking of vehicles can be roughly divided into two types, single-wheel braking and multi-wheel braking. The braking force provided by the multi-wheel braking scheme is greater than that of the single-wheel braking scheme, but at the same time, the impact generated by the double-wheel braking scheme in the active braking process is also relatively large. In addition, the additional yaw moment generated by the wheel braking scheme is also larger. Therefore, in the face of emergencies, a multi-wheel braking scheme with faster control speed and larger upper limit of additional yaw moment is often adopted.

During the turning, the effects of braking different wheels on the steering dynamic performance are different, and the single-wheel control strategy will select different wheels for control under different vehicle states. If it is a two-wheel braking scheme, when the car is about to flick or understeer, the system will adopt the method of active braking the two wheels on the outer side of the vehicle’s rotation direction at the same time to adjust the body state. The two wheels on the inner side of the steering wheel perform active braking to correct the body condition.

Then, it is necessary to select the most effective wheel to generate Td according to the actual situation. If the front wheels cannot provide enough additional yaw moment, the remaining yaw moment can be generated by the training wheels. In order to design the wheel selection strategy, define the following formula:

ƛ=ƛMƛγ,ƛM=sgnTd,ƛγ=sgnr(27)

As shown in Figure 7, the wheel selection strategy is proposed based on ƛM and ƛγ. In Figure 7 [left front, right front wheel, rear left and right rear wheel], when the value in the vector is set to 1, corresponding tire brakes, when the value in the vector is set to 0, tire don’t brake, 0|1 said whether need the auxiliary brake wheel brake, for example, if the right front wheel braking does not produce enough yawing moment, we need to brake the right rear wheel to generate enough yaw torque. If the vehicle is oversteering (ƛ<0), the priority braking wheels are the front outer wheels of the vehicle. When the vehicle understeers (ƛ>0), the priority braking wheel is the rear inner wheel. Once the yaw moment provided by the front wheels is not enough, the remaining yaw moment can be generated by the selected auxiliary wheels.

FIGURE 7
www.frontiersin.org

FIGURE 7. Tire selection strategy.

Finally, according to the selected braking wheels, the distributed four-wheel braking force can be obtained from Formula. 26.

Simulation experiments

In order to verify the effectiveness of the algorithm in this paper, a joint simulation model was built in Carsim and MATLAB/Simulink, as shown in Figure 8. During the operation of the collision avoidance algorithm, the vehicle is driving at a speed of about 84 km/h. The obstacle car is located at (40, −2) position, as shown in Figure 9B. At this time, the vehicle is about to have a frontal collision, and the collision avoidance algorithm starts to run and the steering wheel is turned to the right. As shown in Table 1, the simulated vehicle parameters are selected from Carsim.

FIGURE 8
www.frontiersin.org

FIGURE 8. Carsim simulation diagram.

FIGURE 9
www.frontiersin.org

FIGURE 9. (A) Ego vehicle speed (B) Obstacle avoidance trajectory.

TABLE 1
www.frontiersin.org

TABLE 1. Vehicle parameters.

Without the stability control

Without the stability control, the planning algorithm and the lateral control algorithm as shown in Figures 9, 10 perceive that there is a slow-moving car at a speed of 10 km/h 40 m ahead, and then start to perform lane change to avoid obstacles. After about 2 s, the ego vehicle avoids obstacles, and in about 6 s, the heading angle gradually stabilizes near 0, but the yaw angle speed stabilizes slowly. At this time, the longitudinal velocity vx of the ego vehicle remains basically unchanged.

FIGURE 10
www.frontiersin.org

FIGURE 10. (A) Variation of yaw rate with time (B) Variation of heading angle with time.

The tracking performance can be represented by the change of lateral error (The distance between the vehicle and its projection to the planned path) with time, as shown in the following Figure 11.

FIGURE 11
www.frontiersin.org

FIGURE 11. Variation of lateral error with time.

With the stability control

The stability control intervenes within 2–4 s after the vehicle avoids the obstacle as shown in Figures 12, 13. At this time, the change of the yaw rate is quickly suppressed. At the same time, it can be seen that the heading angle stabilizes rapidly to 1° in 2.5 s. But there is a certain heading angle error. The reason why 2–4 s is chosen is due to the consideration of stability control on path tracking accuracy. Firstly, before avoiding obstacles (that is, before 2 s, this time is calculated by TTC), the stability control has a certain impact on obstacle avoidance, and may even lead to accidents, which should be avoided as much as possible. Secondly, if the stability control intervention time is too long or the stability control intervenes when the yaw angle is large, the lateral control algorithm cannot control the heading angle error to zero. This will cause the planning control algorithm to be unable to track the path stably according to the road centerline after the lane change. The change of tyre braking force with time as shown in Figure 14.

FIGURE 12
www.frontiersin.org

FIGURE 12. (A) Vehicle speed (B) Obstacle avoidance trajectory.

FIGURE 13
www.frontiersin.org

FIGURE 13. (A) Changes of yaw rate with time (B) Changes of heading angle with time.

FIGURE 14
www.frontiersin.org

FIGURE 14. Change of tyre braking force with time.

Trajectory planning

On the premise of keeping other planning parameters consistent, we changed Wpsmooth2 from 1000 to 20,000 for a total of 20 tests (indicated by different colored trajectories). It can be seen that our algorithm successfully avoided the obstacle car ahead under the condition of considering the smooth trajectory as shown in Figure 15, which proves the effectiveness of our algorithm.

FIGURE 15
www.frontiersin.org

FIGURE 15. Trajectory planning.

6 Conclusion

In this paper, the planning algorithm during steering and collision avoidance is studied based on the information and data given by vehicle environmental information perception and vehicle state parameter estimation The coordinated control of vehicle stability and safety is studied. The paper has carried out the following work: 1. Considering the calculation efficiency and control requirements of the model, a three-degree-of-freedom vehicle dynamics model and a linear tire model are established. 2. The planning module is proposed by the method of quadratic programming. This module will plan the driving trajectory of the vehicle by comprehensively considering the constraints and safety of vehicle execution. 3. Considering the vehicle trajectory tracking performance and stability, LQR lateral control and adaptive MPC control algorithms are proposed and the intervention time is proposed. 4. According to the results output by the MPC algorithm, the four-wheel braking force is distributed to realize the vehicle collision avoidance control under the comprehensive consideration of safety and stability. The results show that the planning algorithm in this paper can give a safe and reliable collision-free motion trajectory, and the proposed stability and safety coordination control algorithm can track the collision avoidance trajectory with high precision and stabilize the vehicle’s heading angle about 0.5s after avoiding obstacles.

Data availability statement

The original contributions presented in the study are included in the article/Supplementary Material, further inquiries can be directed to the corresponding author.

Author contributions

All authors listed have made a substantial, direct, and intellectual contribution to the work, and approved it for publication.

Funding

Project supported by National Natural Science Foundation of China (Grant No. 52075388).

Conflict of interest

Author LZ was employed by Global Technology Co., Ltd.

The remaining author declares that the research was conducted in the absence of any commercial or financial relationships that could be construed as a potential conflict of interest.

Publisher’s note

All claims expressed in this article are solely those of the authors and do not necessarily represent those of their affiliated organizations, or those of the publisher, the editors and the reviewers. Any product that may be evaluated in this article, or claim that may be made by its manufacturer, is not guaranteed or endorsed by the publisher.

References

Borrello, G., Raffone, E., Rei, C., and Fossanetti, M. (2020). “Trajectory Planning and Vehicle Control at low speed for home zone manoeuvres,” in 21st IFAC World Congress on Automatic Control - Meeting Societal Challenges), Berlin,Germany, July12–17,2020, 15516–15523.

CrossRef Full Text | Google Scholar

Chen, X., Wu, G., and Ren, M. (2020). Nonlinear model predictive control of autonomous vehicles considering dynamic stability constraints. SAE Int. J. Adv. Curr. Pract. Mobil. 2 (5), 2974–2986. doi:10.4271/2020-01-1400

CrossRef Full Text | Google Scholar

Cheng, Y., Hu, X., Chen, K., Yu, X., and Luo, Y. (2022). Online longitudinal trajectory planning for connected and autonomous vehicles in mixed traffic flow with deep reinforcement learning approach. J. Intelligent Transp. Syst., 1–15. doi:10.1080/15472450.2022.2046472

CrossRef Full Text | Google Scholar

Coelingh, E., Eidehall, A., and Bengtsson, M. (2010). “Collision warning with full auto brake and pedestrian detection - a practical example of automatic emergency braking,” in 13th International IEEE Conference on Intelligent Transportation Systems), Funchal, Portugal, 19-22 September 2010, 155–160.

CrossRef Full Text | Google Scholar

Cui, Q., Ding, R., Wei, C., and Zhou, B. (2021). A hierarchical framework of emergency collision avoidance amid surrounding vehicles in highway driving. Control Eng. Pract. 109, 104751. doi:10.1016/j.conengprac.2021.104751

CrossRef Full Text | Google Scholar

Ge, L., Zhao, Y., Ma, F., and Guo, K. (2022). Towards longitudinal and lateral coupling control of autonomous vehicles using offset free MPC. Control Eng. Pract. 121, 105074. doi:10.1016/j.conengprac.2022.105074

CrossRef Full Text | Google Scholar

Gilbert, A., Petrovic, D., Pickering, J. E., and Warwick, K. (2021). Multi-attribute decision making on mitigating a collision of an autonomous vehicle on motorways. Expert Syst. Appl. 171, 114581. doi:10.1016/j.eswa.2021.114581

CrossRef Full Text | Google Scholar

Han, I. C., Luan, B. C., and Hsieh, F. C. (2014). “Development of Autonomous Emergency Braking control system based on road friction,” in 2014 IEEE International Conference on Automation Science and Engineering (CASE), New Taipei, Taiwan, 18-22 August 2014, 933–937.

CrossRef Full Text | Google Scholar

Hang, J. Y., Yan, X. D., Li, X. M., and Duan, K. (2022). In-vehicle warnings for work zone and related rear-end collisions: A driving simulator experiment. Accid. Analysis Prev. 174, 106768. doi:10.1016/j.aap.2022.106768

CrossRef Full Text | Google Scholar

Li, G., Yang, Y., Zhang, T., Qu, X., Cao, D., Cheng, B., et al. (2021). Risk assessment based collision avoidance decision-making for autonomous vehicles in multi-scenarios. Transp. Res. Part C-Emerging Technol. 122, 102820. doi:10.1016/j.trc.2020.102820

CrossRef Full Text | Google Scholar

Li, P., Pei, X., Chen, Z., Zhou, X., and Xu, J. (2022). Human-like motion planning of autonomous vehicle based on probabilistic trajectory prediction. Appl. Soft Comput. 118, 108499. doi:10.1016/j.asoc.2022.108499

CrossRef Full Text | Google Scholar

Li, Z. H., Wang, P., Liu, H. H., Hu, Y. F., and Chen, H. (2021). Coordinated longitudinal and lateral vehicle stability control based on the combined-slip tire model in the MPC framework. Mech. Syst. Signal Process. 161, 107947. doi:10.1016/j.ymssp.2021.107947

CrossRef Full Text | Google Scholar

Liu, W., Xia, X., Xiong, L., Lu, Y., Gao, L., and Yu, Z. (2021). Automated vehicle sideslip angle estimation considering signal measurement characteristic. IEEE Sensors J. 21 (19), 21675–21687. doi:10.1109/JSEN.2021.3059050

CrossRef Full Text | Google Scholar

Liu, W., Xiong, L., Leng, B., Meng, H., and Zhang, R. (2017). Vehicle stability criterion research based on phase plane method. SAE Technical Paper 2017-01-1560. doi:10.4271/2017-01-1560

CrossRef Full Text | Google Scholar

Liu, W., Xiong, L., Xia, X., and Yu, Z. (2018). “Intelligent vehicle sideslip angle estimation considering measurement signals delay,” in 2018 IEEE Intelligent Vehicles Symposium (IV), Changshu, China, 26-30 June 2018, 1584–1589.

CrossRef Full Text | Google Scholar

Rabhi, A. E. d., Hartani, K., Guettaf, Y., and Norediene, A. (2021). Robust multimachine control for bisynchronous propulsion traction chain of an electric vehicle. Sae Int. J. Veh. Dyn. Stab. Nvh 5 (2), 173–189. doi:10.4271/10-05-02-0012

CrossRef Full Text | Google Scholar

Ren, M., and Wu, G. (2020). “Integrated strategy for automatic lane-changing decision and trajectory planning in dynamic scenario,” in ASME 2020 International Design Engineering Technical Conferences and Computers and Information in Engineering Conference, (V004T04A005).

CrossRef Full Text | Google Scholar

Schieben, A., Griesche, S., Hesse, T., Fricke, N., and Baumann, M. (2014). Evaluation of three different interaction designs for an automatic steering intervention. Transp. Res. Part F-Traffic Psychol. Behav. 27, 238–251. doi:10.1016/j.trf.2014.06.002

CrossRef Full Text | Google Scholar

Tork, N., Amirkhani, A., and Shokouhi, S. B. (2021). An adaptive modified neural lateral-longitudinal control system for path following of autonomous vehicles. Eng. Sci. Technology-an Int. Journal-Jestech 24 (1), 126–137. doi:10.1016/j.jestch.2020.12.004

CrossRef Full Text | Google Scholar

Wu, G. (2021). Automotive theory. 3rd ed. Beijing: China Communications Press.

Google Scholar

Wu, G., Lyu, Z., and Wang, C. (2023). Predictive shift strategy of dual-clutch transmission for driving safety on the curve road combined with an electronic map. SAE Int. J. Veh. Dyn. Stab. NVH 7 (1), 1–19. doi:10.4271/10-07-01-0001

CrossRef Full Text | Google Scholar

Xia, X., Xiong, L., Liu, W., and Yu, Z. (2018). “Automated vehicle attitude and lateral velocity estimation using a 6-D IMU aided by vehicle dynamics,” in 2018 IEEE Intelligent Vehicles Symposium (IV), Changshu, China, 26-30 June 2018, 1563–1569.

CrossRef Full Text | Google Scholar

Xiao, W., Cassandras, C. G., and Belta, C. A. (2021). Bridging the gap between optimal trajectory planning and safety-critical control with applications to autonomous vehicles. Automatica 129, 109592. doi:10.1016/j.automatica.2021.109592

CrossRef Full Text | Google Scholar

Xiong, L., Xia, X., Lu, Y., Liu, W., Gao, L., Song, S., et al. (2020). IMU-based automated vehicle body sideslip angle and attitude estimation aided by GNSS using parallel adaptive kalman filters. IEEE Trans. Veh. Technol. 69 (10), 10668–10680. doi:10.1109/TVT.2020.2983738

CrossRef Full Text | Google Scholar

Yang, C., Chen, X., Lin, X., and Li, M. (2022). Coordinated trajectory planning for lane-changing in the weaving areas of dedicated lanes for connected and automated vehicles. Transp. Res. Part C-Emerging Technol. 144, 103864. doi:10.1016/j.trc.2022.103864

CrossRef Full Text | Google Scholar

Zha, Y., Quan, X., Ma, F., Liu, G., Zheng, X., and Yu, M. (2021). Stability control for a four-wheel-independent-drive electric vehicle based on model predictive control. SAE Int. J. Veh. Dyn. Stab. NVH 5 (2), 191–204. doi:10.4271/10-05-02-0013

CrossRef Full Text | Google Scholar

Zhang, R., Xiong, L., Yu, Z., and Liu, W. (2017). A nonlinear dynamic control design with conditional integrators applied to unmanned skid-steering vehicle. SAE Technical Paper 2017-01- 1585. doi:10.4271/2017-01-1585

CrossRef Full Text | Google Scholar

Keywords: trajectory planning, stability control, LQR lateral control, emergency collision avoidance, direct yaw moment control

Citation: Liu Z, Wen G, Liu W, Tan T and Wu G (2023) Research on automatic emergency steering collision avoidance and stability control of intelligent driving vehicle. Front. Robot. AI 10:1120658. doi: 10.3389/frobt.2023.1120658

Received: 10 December 2022; Accepted: 06 February 2023;
Published: 21 February 2023.

Edited by:

Xin Xia, University of California, Los Angeles, United States

Reviewed by:

Wei Liu, Purdue University, United States
Weihua Li, Harbin Institute of Technology, Weihai, China

Copyright © 2023 Liu, Wen, Liu, Tan and Wu. This is an open-access article distributed under the terms of the Creative Commons Attribution License (CC BY). The use, distribution or reproduction in other forums is permitted, provided the original author(s) and the copyright owner(s) are credited and that the original publication in this journal is cited, in accordance with accepted academic practice. No use, distribution or reproduction is permitted which does not comply with these terms.

*Correspondence: Guangqiang Wu, wuguangqiang@tongji.edu.cn

Download