Next Article in Journal
Using an Intelligent Control Method for Electric Vehicle Charging in Microgrids
Next Article in Special Issue
Analysis of Active Suspension Control Based on Improved Fuzzy Neural Network PID
Previous Article in Journal
State of Charge Estimation of Lithium-Ion Batteries Based on an Improved Sage-Husa Extended Kalman Filter Algorithm
Previous Article in Special Issue
Model-Based Fault Diagnosis of Actuators in Electronically Controlled Air Suspension System
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

MPC-Based Obstacle Avoidance Path Tracking Control for Distributed Drive Electric Vehicles

School of Mechanical and Automotive Engineering, Shanghai University of Engineering Science, Shanghai 201620, China
*
Author to whom correspondence should be addressed.
World Electr. Veh. J. 2022, 13(12), 221; https://doi.org/10.3390/wevj13120221
Submission received: 6 October 2022 / Revised: 11 November 2022 / Accepted: 16 November 2022 / Published: 22 November 2022

Abstract

:
A path tracking controller based on front wheel steering angle and additional yaw moment control is designed to achieve safe obstacle avoidance of distributed drive electric vehicles. Using sixth-degree polynomial at a given time with anti-collision and anti-rollover conditions, the path planning of obstacle avoidance is proposed. The front wheel steering angle and additional yaw moment are output by the Model Predictive Control (MPC) controller. The wheel torque is distributed by the torque distribution controller. Through additional yaw moment and the vertical force ratio of the wheel, the obstacle avoidance path tracking control is realized. The co-simulation platform is established with Carsim/Simulink. The obstacle avoidance path, model predictive controller and torque distribution controller designed in this paper are simulated. The results show that obstacle avoidance path and tracking controller for the distributed drive electric vehicles effectively meet the requirements of safe obstacle avoidance.

1. Introduction

With the continuous increase in car ownership, the modern intelligent transportation system has increasingly regarded vehicle safety as its key factor. Between 2002 and 2012, the lack of proper obstacle avoidance contributed to the deaths of millions of people in traffic accidents around the world, and the economic cost of these accidents amounted to $0.48 trillion [1]. More than 90% of these accidents are caused by human factors [2]. Therefore, in order to avoid vehicle collisions and minimize the impact of accidents, a method of adding an increasing proportion of active safety systems is proposed [3].
The obstacle avoidance trajectory tracking control of intelligent vehicles is one of the key functions. According to the trajectory planned by the upper controller and the real-time state information, real-time vehicle control variables, such as front wheel angle and driving force/braking force, are generated [4]. Compared with traditional vehicles, the drive motors are directly installed in the drive wheels for the distributed drive electric vehicles. So they have outstanding advantages, such as short drive transmission chain, high transmission efficiency and compact structure. It can be more beneficial to realize the tracking control of the obstacle avoidance path by optimizing the distribution of the driving torque of each wheel [5]. Although distributed hub motors can lead to greater unsprung mass, a small amount of unsprung mass increase is negligible, given their advantages in dynamic control.
After the continuous development of path tracking control, different tracking control algorithms have been proposed and verified, such as sliding mode control, fuzzy control, and model predictive control. Reference [6] proposed a distributed drive unmanned vehicle path tracking and stability coordinated control strategy based on the layered control theory. In order to reduce the heading deviation and lateral deviation during the path-tracking process, the sliding mode control method was used. Moreover, it can ensure the stability of the vehicle. On the basis of the traditional dynamic model and preview model, Zhang Bingli [7] designed a new trajectory-tracking controller based on neural networks and fuzzy control theory. Wang Yao [8] proposed a model prediction-fuzzy (MPC-Fuzzy) joint control strategy, which alleviated the conflict between the vehicle tracking accuracy and the controller’s computational pressure under a single model prediction control and better solved the distributed driving vehicle path, tracking accuracy and stability issues in tracking. Hu [9] designed a fuzzy linear quadratic regulator (LQR) with preview PID angle compensation and verified that it can maintain good accuracy and stability at different vehicle speeds. However, it also had the problem of low tracking accuracy when the vehicle was running at a low speed. Kou [10] used a state expansion MPC and corner compensation fuzzy controller, designed a dual feedback MPC controller based on state expansion and verified that it had better path tracking performance at medium and low vehicle speeds. Wu [11] proposed a front-wheel steering controller and optimized the controller parameters so that the vehicle had better path-tracking performance at low and medium speeds and ensured that the vehicle had certain steering accuracy and driving stability when driving at high speed on ice and snow roads. In order to improve the stability of distributed drive electric vehicles in extreme working conditions, Li [12] proposed a nonlinear model predictive control (NMPC) based torque coordination control strategy. In order to coordinate the trajectory tracking accuracy and stability of distributed drive electric vehicles and improve the adaptive ability of the control algorithm to different working conditions, Zhuang [13] proposed a trajectory tracking control strategy based on Takagi–Sugeno fuzzy model predictive control (T-S FMPC).
The total required torque is calculated through the yaw moment obtained by the upper controller. The torque distributed to each drive wheel is obtained through different algorithms. There are many distribution methods for torque distribution. A fixed proportional distribution method was proposed in the literature [14,15]. Although this method was simple, it cannot implement different proportional distributions according to different road conditions. There was no optimization in the energy utilization efficiency of the motor, and the best distribution result could not be achieved. Ono E [16] proposed to realize the torque distribution to the four wheels according to the usage of the tire force of four tires. This method made the wear degree of the four tires more balanced, and the life of the tires and the motor were improved, but the performance of vehicle handling was greatly reduced. Mokhiamar O [17] also proposed to analyze the torque distribution problem by establishing a multi-objective optimization function, but this method may show different effects in different models and different operating conditions, so the consistency and robustness were poor. Reference [18] considered the dynamic characteristics of the vehicle when it is unstable and proposed a control allocation scheme based on feedback linearization. This scheme was relatively dependent on the accuracy of the model and had poor stability. Reference [19] distributed torque according to the vertical load distribution ratio of each wheel. Since the friction ellipse of the tire increases with the increase of the vertical load, the torque distribution according to the vertical load ratio of a single tire can avoid the saturation of the tire force and can simply and effectively improve the driving stability of the vehicle.
Based on the above analysis, the whole vehicle control process designed in this paper is shown in Figure 1. In Section 1, using the obstacle information obtained by the environment awareness layer and the vehicle pose information detected by the vehicle sensor, the obstacle avoidance path is planned. Anti-collision and anti-rollover constraints adding to a six-degree polynomial are used for path planning. The front wheel angle δf and additional yaw moment ∆Mz are output by the MPC controller in Section 3.2. By processing the information of the path planning layer, the torque distribution controller distributes the torque through the additional yaw moment and the wheel vertical force ratio in Section 3.3. The MPC controller and the torque distribution controller together form a path-tracking controller. During the obstacle avoidance process, the vehicle avoids obstacles through the front wheel angle and four-wheel torque output by the controller. In Section 4, the simulation platform is established, and the effect of the controllers is verified.

2. Path Planning

In this paper, the six-degree polynomial path planning method [20] for a given time is used. In the sixth-degree polynomial path planning method, the vehicle’s gentle arrival from the starting point to the target point is considered, the collision between the vehicle and the obstacle in the process of running is considered, and the smooth running according to the planned path is also considered. With the addition of anti-collision and anti-rollover conditions, the safety of obstacle avoidance path planning is improved.
Based on the longitudinal and lateral displacements at a given time, the initial expression for the sixth-degree polynomial is:
{ X ( t ) = c 0 + c 1 t + c 2 t 2 + c 3 t 3 + c 4 t 4 + c 5 t 5 + c 6 t 6 Y ( t ) = b 0 + b 1 t + b 2 t 2 + b 3 t 3 + b 4 t 4 + b 5 t 5 + b 6 t 6
Adding anti-collision conditions [20]: set the coordinate center of the obstacle as (Xob, Yob), and the radius of the circumscribed circle of the vehicle and the obstacle as Rcar and Rob, this is shown in Figure 2,the constraint condition of anti-collision can be expressed as:
( R c a r + R o b ) 2 < [ X ( t ) X o b ] 2 + [ Y ( t ) Y o b ] 2
Adding the anti-rollover condition constraint [20].
According to the simplified model diagram of vehicle rollover in Figure 3, the moment balance equation can be expressed as:
m s a y h + m s g Δ y = ( F z l F z r ) s 2
where, ay is the lateral acceleration, m s is the sprung mass, h is the distance from the center of mass to the ground, F z l represents the sum of forces on the left front and rear wheels in the vertical direction, F z r represents the sum of forces on the right front and rear wheels, s represents the track width, g is the gravitational acceleration, Δ y = h sin ϕ .
The lateral transfer rate of the vehicle is:
LTR = F zl F zr F zl + F zr
Combining Equations (3) and (4), LTR can be expressed as:
L T R = 2 R s [ a y g + sin ϕ ]
where, ϕ is the vehicle roll angle.
The larger the absolute value of LTR indicates, the greater the rollover risk of the car, so the size of ay should be fully taken into account in path planning. Given the maximum roll risk LTRmax,
a y = Y ¨ ( t ) ( s LTR max 2 h sin ϕ ) g
a y max = ( s LTR max 2 h sin ϕ ) g
Constructing the evaluation index function of anti-rollover:
J a n t i r = t 0 t d ( a y max | a y | ) d t
The polynomial optimization path planning problem is expressed as:
{ min J a n t i r s . t . ( R c a r + R o b ) 2 < [ X ( t ) X o b ] 2 + [ Y ( t ) Y o b ] 2 a y = Y ¨ ( t ) ( s LTR max 2 h sin ϕ ) g b 3 t d 3 + b 4 t d 4 + b 5 t d 5 + b 6 t d 6 = H 3 b 3 t d 2 + 4 b 4 t d 3 + 5 b 5 t d 4 + 6 b 6 t d 5 = 0 6 b 3 t d + 12 b 4 t d 2 + 20 b 5 t d 3 + 30 b 6 t d 4 = 0
where, t0 and td are the initial time and the end time, respectively, ay is the lateral acceleration, Xob and Yob are the coordinate centers of the obstacles, the coordinate center of the obstacle:(Xob, Yob) = (100, 1), Rcar and Rob are the radiuses of the circumscribed circles between the vehicle and the obstacle, is the body roll angle, and w is the wheelbase, h is the distance from the center of mass to the ground, g is the acceleration of gravity, H is the self-conjugate matrix, Janti-r is the anti-rollover evaluation index function, and LTR is the roll risk coefficient.
In Equation (9), the coefficients b3, b4, b5 and b6 can be obtained by the optimization algorithm.
The yaw angle can be expressed as:
φ ( t ) = arctan d Y ( t ) d X ( t ) = arctan Y ˙ ( t ) X ˙ ( t )

3. Path Tracking Control

3.1. Establishment of Vehicle Dynamics Model

The three-degree-of-freedom vehicle dynamics model is shown in Figure 4, including lateral motion, yaw motion and longitudinal motion [21,22]. The aerodynamics, suspension system and steering system are ignored. Considering that the sideslip angle of the center of mass is small when the lateral acceleration is not high, the control accuracy will not be affected if it is ignored, so the sideslip angle of the center of mass is ignored [23]. According to the characteristics of the distributed drive vehicle, the additional yaw moment is considered.
In Figure 4, the coordinate axis oxyz is the fixed coordinate system of the vehicle, xoz is in the left-right symmetrical plane of the vehicle, the coordinate origin of the center of mass of the vehicle is o, the x-axis is the coordinate axis along the longitudinal direction of the vehicle, and the y-axis is the coordinate perpendicular to the longitudinal direction of the vehicle axis. The z-axis is the coordinate axis perpendicular to the xoy plane, and the direction satisfies the right-hand rule. XOY is the geodetic coordinate system. Considering that Fxf and Fyf are the force exerted on a single tire, it needs to be multiplied by 2. According to Newton’s second law:
{ m x ¨ = m y ˙ φ ˙ + 2 F x f + 2 F x r m y ¨ = m x ˙ φ ˙ + 2 F y f + 2 F y r I z φ ¨ = 2 l f F y f 2 l r F y r
where lf and lr are the distances from the center of mass to the front and rear axles, respectively. m is the overall mass of the vehicle, and Iz is the central moment of inertia of the vehicle around the z axis.
The conversion relationship between the resultant force of the tire in the x-direction and y-direction, the longitudinal force and the lateral force is expressed as follows:
{ F x f = F l f cos δ f F c f sin δ f F x r = F l r cos δ f + F c r sin δ r F y f = F l f sin δ f + F c f cos δ f F y r = F c r cos δ r F l r sin δ f
where Fxf and Fyf are the resultant forces on the front wheels in the x and y directions, respectively. Fxr and Fyr are the resultant forces on the front wheels in the x and y directions, respectively, and Flf and Flr are the longitudinal forces on the front and rear wheels, respectively. Fcf and Fcr are the lateral forces on the front and rear wheels, respectively. δf is the front wheel angle, δr is the rear wheel angle.
The lateral and longitudinal forces of vehicle tires can be expressed as complex functions of parameters such as wheel slip angle, slip rate, road friction coefficient and vertical load:
F c = f c ( α , s , μ , F z )
F l = f l ( α , s , μ , F z )
where, Fz is the vertical load on the tire, μ is the road friction coefficient, s is the slip ratio, and α is the wheel side angle.
In order to simplify the model, the tire force is usually represented by a linear function under the condition of small tire longitudinal slip rate, lateral acceleration and slip angle. The force is expressed as follows:
{ F l = C l s F c = C c α
where Cl is the longitudinal stiffness of the vehicle tire, and Cc is the cornering stiffness of the vehicle tire.
The following approximate relationship is satisfied:
{ cos θ 1 sin θ θ tan θ θ
where θ can be expressed as front wheel side angle and rear wheel side slip angle, etc.
The wheel side slip angle α can be obtained according to the geometric relationship:
α = tan 1 v c v l
where vc and vl represent the lateral and longitudinal speeds of the tire, respectively, which can be represented by the speeds vx and vy in the direction of the coordinate system:
{ v l = v y sin δ + v x cos δ v c = v y cos δ v x sin δ
where δ is the tire deflection angle. The tire speed is generally calculated by the speed conversion of the vehicle, and the conversion relationship is shown in Formula (19):
{ v y f = y ˙ + l f φ ˙ v y r = y ˙ l r φ ˙
{ v x f = x ˙ v x r = x ˙
Through the above formulas, the wheel side slip angle can be obtained as:
{ α f = y ˙ + l f φ ˙ x ˙ δ f α r = y ˙ l r φ ˙ x ˙
From Equation (20), the tire lateral force of the front and rear wheels can be obtained as:
{ F c f = C c f ( δ f y ˙ + l f φ ˙ x ˙ ) F c r = C c r l r φ ˙ y ˙ x ˙
According to the above derivation formula, the following nonlinear vehicle dynamics model can be obtained as follows:
{ m y ¨ = m x ˙ φ ˙ + 2 [ C c f ( δ f y ˙ + l f φ ˙ x ˙ ) + C c r l r φ ˙ y ˙ x ˙ ] m x ¨ = m y ˙ φ ˙ + 2 [ C l f s f + C c f ( δ f y ˙ + l f φ ˙ x ˙ ) δ f + C l f s r ] I z φ ¨ = 2 [ l f C c f ( δ f y ˙ + l f φ ˙ x ˙ ) l r C c r l r φ ˙ y ˙ x ˙ ] + Δ M z Y ˙ = x ˙ sin φ + y ˙ cos φ X ˙ = x ˙ cos φ y ˙ sin φ
In this paper, due to the use of a linear time-varying model predictive control algorithm, the displacement and velocity in the longitudinal direction are not considered as control variables. Let φ ˙ = r, x ˙ = vx, y ˙ = vy, Equation (22) can be simplified as:
{ v ˙ y = C c f + C c r m v x v y ( l f C c f l r C c r m v x + v x ) r + C c f m δ f r ˙ = l f C c f l r C c r I z v x v y l f 2 C c f + l r 2 C c r I z v x r + l f C c f I z δ f + Δ M z I z φ ˙ = r Y ˙ = v x φ + v y
According to the above dynamic model, the following state space equation is established:
{ ξ ˙ = A ξ + B u y = C ξ
where the state quantity ξ = [ v y r φ y ] T , the control quantity u = [ δ f Δ M z ] T , A, B, and C are coefficient matrices, respectively:
A = [ C c f + C c r m v x ( l f C c f l r C c r m v x + v x ) 0 0 l f C c f l r C c r I z v x l f 2 C c f + l r 2 C c r I z v x 0 0 0 1 0 0 1 0 v x 0 ]
B = [ C c f m 0 l f C c f I z 1 I z 0 0 0 0 ]
C = [ 0 0 1 0 0 0 0 1 ]

3.2. MPC Controller Design

The linear time-varying model is shown in Figure 5. In the model, the control value is initial velocity v0 = 18 m/s; The actual measured value is vy, r, φ, y; The control input value is αf, ∆Mz.
Since the linear time-varying model [13] is used, it is necessary to perform linear time-varying processing and discretization processing on Equation (24).
Let Ak = I + AT, Bk = BT, Ck = C.
where T is the sampling time, I is the identity matrix,
A k = [ 1 C c f + C c r m v x T ( l f C c f l r C c r m v x + v x ) T 0 0 l f C c f l r C c r I z v x T 1 l f 2 C c f + l r 2 C c r I z v x T 0 0 0 T 1 0 T 0 v x T 1 ]
B k = [ C c f m T 0 l f C c f I z T T I z 0 0 0 0 ]
C k = [ 0 0 1 0 0 0 0 1 ]
So the following discrete state space equation is obtained:
{ ξ ˙ ( k + 1 ) = A ξ ( k ) + B u ( k ) y ( k ) = C k ξ ( k )
In order to avoid the phenomenon of a sudden change in the control quantity of the system, it is necessary to restrict the control increment in each sampling period, so the above formula of this paper is converted and deformed:
Note: ζ = , substitute into the above formula to obtain a new state space equation:
{ ζ ( k + 1 ) = A ˜ k ζ ( k ) + B ˜ k Δ u ( k ) y ( k ) = C ˜ k ξ ( k )
In the formula,
A ˜ k = [ A k B k 0 3 × 4 I 2 ]
B ˜ k = [ B k I 2 ]
C ˜ k = [ 0 0 1 0 0 0 0 0 0 1 0 0 ]
The optimization objective function of the path tracking and torque distribution controller is expressed as:
J = i = 1 N p y ( k + i ) y r e f ( k + i ) 2 Q + i = 1 N c 1 Δ u ( k + i ) 2 R
where yref is obtained by the path planning layer; Q and R are the trajectory tracking error weight matrix and the control amount increment weight matrix, respectively; Np and Nc are the prediction time domain and the control time domain, respectively. Some parameter settings in model predictive control are shown in Table 1.

3.3. Torque Distribution Controller Design

Torque distribution strategy has a great impact on vehicle lateral stability. Firstly, the additional yaw moment ΔMz output by the MPC controller is used to calculate the total demand torque Tall. Then using the proportion of the vertical load, calculates the torque of the four wheels. On the premise of ensuring lateral stability, the flexible torque distribution is realized.
The additional yaw moment ΔMz and the four-wheel torque should satisfy the following relationship:
Δ M z = b 2 R [ ( T F r T F l ) cos δ f + ( T R r T R l ) ]
where R is the wheel radius, b is the wheel track, and TFl, TFr, TRl and TRr are the torques of the left front wheel, the right front wheel, the left rear wheel and the right rear wheel, respectively.
F z = F z , F l + F z , F r + F z , R l + F z , R r
while:
{ k 1 = F z , F l F z k 2 = F z , F r F z k 3 = F z , R l F z k 4 = F z , R r F z
where Fz,Fl, Fz,Fr, Fz,Rl, Fz,Rr are the vertical loads of the left front wheel, the right front wheel, the left rear wheel and the right rear wheel, respectively. Force, k1, k2, k3, k4 are the proportional coefficients of the four-wheel vertical force and the total vertical force.
According to Equations (37)–(39), the total demand torque Tall and the distributed four-wheel torques TFl, TFr, TRl, TRr can be obtained:
T a l l = Δ M z 2 R d [ ( k 2 k 1 ) cos δ f + ( k 4 k 3 ) ]
{ T F l = k 1 T a l l T F r = k 2 T a l l T R l = k 3 T a l l T R r = k 4 T a l l
The solution of the final path tracking and torque distribution controller can be expressed as:
{ min Z = i = 1 N p y ( k + i ) y r e f ( k + i ) 2 Q + i = 1 N c 1 Δ u ( k + i ) 2 R s . t .   ζ ( k + 1 ) = A ˜ k ζ ( k ) + B ˜ k Δ u ( k ) Δ u min Δ u ( k + i ) Δ u max u min u ( k + i ) u max y min y ( k + i ) y max φ min φ ( k + i ) φ max
The control quantity at time k + 1 can be expressed by the control quantity at time k plus the control increment at time k:
u ( k + 1 ) = u ( k ) + Δ u ( k )

4. Simulation Analysis and Verification

The C-class vehicle model is adopted in Carsim. PD18 in-wheel motor is adopted in the motor model. According to the characteristics of the distributed drive vehicle, the vehicle parameters are shown in Table 2.

4.1. Verification of Co-Simulation Platform

The initial speed of the vehicle is 60 km/h, the road adhesion coefficient μ = 0.8 and the maximum value of LTR is set at 0.1. The simulation results are shown in Figure 6 and Figure 7.
It can be seen from Figure 5 that the controller can accurately track the reference path. The tracking error of the yaw angle is small, and the lateral acceleration appears slightly jittered between 0 and 1 s, but the value of the lateral acceleration is maintained throughout the process. Within a reasonable range, the front wheel corners shake slightly at 0 s to 1 s and 6 s to 7 s, but the changes in the corners are relatively gentle, and the corner values do not exceed the specified value. It can be concluded that the control effect of the controller is good and can meet the needs of vehicle obstacle avoidance.
It can be seen from Figure 6 that the value of LTR is always in a small range during the entire obstacle avoidance process, which verifies the effectiveness of the set obstacle avoidance path and meets the requirements of anti-rollover in the obstacle avoidance process.

4.2. Simulation of Tracking Control Performance

The stability and robustness of the designed path tracking and torque distribution controller are verified by the simulation of different road adhesion coefficient conditions. Select high adhesion pavement coefficient μ = 0.8, low adhesion pavement coefficient μ = 0.2, μ = 0.1. The specific simulation results are shown in Figure 7 and Figure 8.
It can be seen from Figure 8a–d that the tracking control effect of the controller is excellent when the high adhesion coefficient road surface μ = 0.8. The effect is slightly decreased when the low adhesion coefficient road surface μ = 0.2, and the tracking control error is slightly increased. The changes in lateral acceleration and front wheel angle are relatively gentle under both conditions. When μ = 0.1, the vehicle deviates greatly from the planned path and the planned yaw angle. The lateral acceleration and front wheel angle also produce a lot of jitter. This is because the road adhesion coefficient is too low to the adhesion limit. Under this condition, the controller cannot perform tracking control.
It can be seen from Figure 9 that when μ = 0.8 and μ = 0.2, the vertical force changes of the wheels are relatively gentle, which meets the requirements of stable driving of the vehicle in the process of obstacle avoidance. When μ = 0.1, the tires are not sufficient to provide the vehicle with steady longitudinal and lateral force. At 2.5 s and 4.7 s, there is a large jump, which can no longer meet the stability requirements of the vehicle during driving.
Figure 10a–d shows that when μ = 0.8, the torque distribution of each wheel meets the requirements of this paper. When μ = 0.2, the torque of the left front wheel begins to increase after 1 s and reaches a peak at 1.5~3.5 s, the maximum value is 107 N∙m. The torque starts to decrease continuously at 3.5~5 s and 5~5.5 s. It reaches the reverse maximum value of 116 N∙m and then changes to 0 N∙m. The torque changes of the remaining wheels are roughly the same as the torque changes of the left front wheel, so this conclusion description will not be repeated. It can be seen that under this working condition, the controller has a good torque distribution effect. When μ = 0.1, the torque of each wheel drops rapidly to about −100 N∙m in 2 s, and the controller cannot continue to distribute the torque normally.
From the analysis of Figure 9 and Figure 10, it can be seen that the controller designed in this paper can still control the vehicle to drive according to the correct planned path under the condition of low road adhesion coefficient μ = 0.2 and carry out reasonable torque distribution, which verifies the path. The tracking controller has good robustness. When μ = 0.1, the vehicle has already slipped, and the path tracking control can not be realized.

5. Conclusions

(1)
Sixth-order polynomial for obstacle avoidance path planning is presented. Through the simulation results, it is verified that the planned path can be accurately tracked, and the LTR values are always within the safe range. The vehicle has no risk of rollover. The obstacle avoidance path and tracking controller in this paper can effectively meet the requirements of safe obstacle avoidance.
(2)
In this paper, path planning, path tracking and torque distribution are combined to achieve safe obstacle avoidance through the tracking control of the obstacle avoidance path. The path-tracking controller not only realizes the intelligent obstacle avoidance process of unmanned vehicles but also combines it with distributed vehicles. The safety and stability are improved by the torque distribution strategy in the obstacle avoidance process compared with traditional vehicles. Simultaneously, simulations are carried out under different road adhesion coefficient conditions, and the simulation results show that the vehicle can still perform safe and stable automatic obstacle avoidance under the conditions of road adhesion coefficient μ = 0.2, indicating that the controller has good robustness.
This paper provides an idea for the obstacle avoidance path tracking control of distributed drive electric vehicles. In the follow-up research work, the torque distribution controller can be improved, and better torque distribution and anti-skid control can be added to the original design scheme. The control strategy can be realized under the condition of a lower road adhesion coefficient. The real vehicle test link is added to verify the effectiveness of the control strategy in this paper.

Author Contributions

Writing—original draft, H.W.; Writing—review & editing, H.Z. and Y.F. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by National Natural Science Foundation of China grant number 51705306.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. World Health Organization. Global Status Report on Road Safety 2013: Supporting a Decade of Action; World Health Organization: Geneva, Switzerland, 2013.
  2. Toroyan, T. Global status report on road safety. Inj. Prev. 2009, 15, 286. [Google Scholar] [CrossRef] [PubMed]
  3. Chang, S.; Gordon, T. A flexible hierarchical model-based control methodology for vehicle active safety systems. Veh. Syst. Dyn. 2008, 46, 63–75. [Google Scholar] [CrossRef] [Green Version]
  4. Guo, J.; Hu, P.; Wang, R. Nonlinear coordinated steering and braking control of vision-based autonomous vehicles in emergency obstacle avoidance. IEEE Trans. Intell. Transp. Syst. 2016, 17, 3230–3240. [Google Scholar] [CrossRef]
  5. Yu, Z.; Jiang, W.; Zhang, L. Torque distribution control of electric vehicle driven by four wheel hub motor. J. Tongji Univ. Nat. Sci. Ed. 2008, 36, 5. [Google Scholar]
  6. Chen, T.; Chen, L.; Xu, X. Coordinated Control of Path Tracking and Stability of Distributed Driving Unmanned Vehicles. Automot. Eng. 2019, 41, 1109–1116. [Google Scholar]
  7. Zhang, B.; Li, Z.; Shen, G. Research on intelligent vehicle track tracking based on fuzzy neural network. Automot. Eng. 2019, 41, 7. [Google Scholar]
  8. Wang, Y.; Chen, Q.; Gao, L. A distributed driving vehicle path tracking method based on prediction-fuzzy joint control. Sci. Technol. Eng. 2020, 20, 15100–15108. [Google Scholar]
  9. Hu, J.; Zhong, X.; Chen, R. Intelligent Vehicle Path Tracking Control Based on Fuzzy LQR. Automot. Eng. 2022, 44, 17–25. [Google Scholar]
  10. Kou, F.; Zheng, W.; Zhang, X.; Yang, H.; He, J. Path following control of unmanned vehicle using state extended MPC and corner compensation. Mech. Sci. Technol. Aerosp. Eng. 2022, 4, 1–8. [Google Scholar]
  11. Wu, F.; Guo, S. Intelligent vehicle path tracking algorithm based on nonlinear model predictive control. Automot. Technol. 2020, 5, 1–7. [Google Scholar]
  12. Li, S.; Yang, Z.; Wang, X. Trajectory Tracking Control of Intelligent Vehicle Based on T-S Fuzzy Variable Weight MPC. J. Mech. Eng. 2022, 15, 1–14. [Google Scholar]
  13. Zhuang, Y.; Wu, Y.; Zhang, B. Coordinated Torque Control of Distributed Drive Electric Vehicle Based on Nonlinear MPC. J. Vib. Shock. 2021, 40, 9. [Google Scholar]
  14. Shino, M.; Nahai, M. Yaw-moment control of electric vehicle for improving handling and stability. JSAE Rev. 2001, 22, 473–480. [Google Scholar] [CrossRef]
  15. Zou, G.; Luo, Y.; Li, K. Optimal distribution method of all-wheel longitudinal force for four-wheel independent electric vehicle. J. Tsinghua Univ. Nat. Sci. Ed. 2009, 49, 719–722. [Google Scholar]
  16. One, E.; Hattori, Y.; Muragishi, Y. Vehicle dynamics integrated control for four-wheel-distributed steering and four-wheel-distributed traction/braking systems. Veh. Syst. Dyn. 2006, 44, 139–151. [Google Scholar] [CrossRef]
  17. Mokhiamar, O.; Abe, M. How the four wheels should share forces in an optimum cooperative chassis control. Control Eng. Pract. 2006, 14, 295–304. [Google Scholar] [CrossRef]
  18. Yu, Z.; Yang, P.; Xiong, L. Application of Control Distribution Theory in Vehicle Dynamics Control. Chin. J. Mech. Eng. 2014, 50, 99–107. [Google Scholar] [CrossRef]
  19. Mutoh, N. Driving and braking torque distribution methods for front-and rear-wheel-independent drive-type electric vehicles on roads wit low friction coefficient. IEEE Trans. Ind. Electron. 2012, 59, 3919–3933. [Google Scholar] [CrossRef]
  20. Yang, B.; Zhang, W.; Jiang, Z. Simulation analysis of obstacle avoidance path planning and tracking control for intelligent vehicles. China Test 2021, 47, 71–78. [Google Scholar]
  21. Ren, Y.; Zheng, L.; Zhang, W. Research on Active Collision Avoidance Control of Intelligent Vehicles Based on Model Predictive Control. Automot. Eng. 2019, 41, 405–410. [Google Scholar]
  22. Zhang, F.; Wei, M.; Huang, L. Research on vehicle emergency lane change control based on model predictive control. Mod. Manuf. Eng. 2017, 3, 57–64. [Google Scholar]
  23. Gong, J.; Jiang, W.; Xu, W. Model Predictive Control for Self-Driving Vehicles, 1st ed.; Beijing Institute of Technology Press: Beijing, China, 2014; pp. 22–25. [Google Scholar]
Figure 1. Vehicle control flow chart. Where, Xc0 and Yc0 are the lateral distance and longitudinal distance from the obstacle; vc is the vehicle speed of the obstacle; Xd and Yd are the expected lateral and longitudinal distance of the vehicle; φd is the expected yaw angle of the vehicle; ∆Mz is the additional yaw moment; Tfl, Trl, Trr and Tfr are the torques of the left front wheel, the left rear wheel, the right rear wheel and the right front wheel, respectively; X and Y are the transverse and vertical coordinates under the inertial coordinate system; φ is the yaw angle under the body coordinate system; r is the turning radius of the vehicle; vx and vy are the lateral and speed longitudinal of the vehicle; ax is the lateral acceleration of the vehicle.
Figure 1. Vehicle control flow chart. Where, Xc0 and Yc0 are the lateral distance and longitudinal distance from the obstacle; vc is the vehicle speed of the obstacle; Xd and Yd are the expected lateral and longitudinal distance of the vehicle; φd is the expected yaw angle of the vehicle; ∆Mz is the additional yaw moment; Tfl, Trl, Trr and Tfr are the torques of the left front wheel, the left rear wheel, the right rear wheel and the right front wheel, respectively; X and Y are the transverse and vertical coordinates under the inertial coordinate system; φ is the yaw angle under the body coordinate system; r is the turning radius of the vehicle; vx and vy are the lateral and speed longitudinal of the vehicle; ax is the lateral acceleration of the vehicle.
Wevj 13 00221 g001
Figure 2. Schematic diagram of collision avoidance.
Figure 2. Schematic diagram of collision avoidance.
Wevj 13 00221 g002
Figure 3. Simplified model of automobile rollover.
Figure 3. Simplified model of automobile rollover.
Wevj 13 00221 g003
Figure 4. Three-degree-of-freedom vehicle dynamics model.
Figure 4. Three-degree-of-freedom vehicle dynamics model.
Wevj 13 00221 g004
Figure 5. Flow chart of linear time-varying model control.
Figure 5. Flow chart of linear time-varying model control.
Wevj 13 00221 g005
Figure 6. Co-simulation results. (a) Path tracking. (b) Yaw angle tracking. (c) Lateral acceleration. (d) Front-wheel turning angle.
Figure 6. Co-simulation results. (a) Path tracking. (b) Yaw angle tracking. (c) Lateral acceleration. (d) Front-wheel turning angle.
Wevj 13 00221 g006
Figure 7. Changes in LTR value.
Figure 7. Changes in LTR value.
Wevj 13 00221 g007
Figure 8. Simulation comparison under different road adhesion coefficient conditions. (a) Path tracking. (b) Yaw tracking. (c) Front-wheel angle. (d) Lateral acceleration.
Figure 8. Simulation comparison under different road adhesion coefficient conditions. (a) Path tracking. (b) Yaw tracking. (c) Front-wheel angle. (d) Lateral acceleration.
Wevj 13 00221 g008
Figure 9. Comparison of vertical forces on wheels. (a) vertical force of left wheel; (b) vertical force of right wheel.
Figure 9. Comparison of vertical forces on wheels. (a) vertical force of left wheel; (b) vertical force of right wheel.
Wevj 13 00221 g009
Figure 10. Comparison of torque distribution among wheels. (a) Torque comparison of left front wheel. (b) Torque comparison of left rear wheel. (c) Torque comparison of right front wheel. (d) Torque comparison of right rear wheel.
Figure 10. Comparison of torque distribution among wheels. (a) Torque comparison of left front wheel. (b) Torque comparison of left rear wheel. (c) Torque comparison of right front wheel. (d) Torque comparison of right rear wheel.
Wevj 13 00221 g010aWevj 13 00221 g010b
Table 1. Part of the parameter settings of the controller.
Table 1. Part of the parameter settings of the controller.
Parameter NameValue
Nc8
Np25
Δ u m i n −0.02
Δ u m a x 0.2
a y m i n −0.25 g
a y m a x 0.25 g
Q[2000 0; 0 2000]
R[3000 0; 0 1]
Table 2. The vehicle model parameters.
Table 2. The vehicle model parameters.
ParametersValue
Vehicle sprung mass m s / kg 1743
Vehicle mass m/kg1907
Moment of inertia I z / ( kg m 2 ) 3246.9
front wheelbase l f /m1.33
rear wheelbase l r /m1.81
The height of the center of mass above the ground h/m0.781
Wheeltrack b/m2.029
Lateral stiffness of front wheels   C c f / ( N rad 1 ) 116,050
Lateral stiffness of rear wheels C c r / ( N rad 1 ) 104,590
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Wu, H.; Zhang, H.; Feng, Y. MPC-Based Obstacle Avoidance Path Tracking Control for Distributed Drive Electric Vehicles. World Electr. Veh. J. 2022, 13, 221. https://doi.org/10.3390/wevj13120221

AMA Style

Wu H, Zhang H, Feng Y. MPC-Based Obstacle Avoidance Path Tracking Control for Distributed Drive Electric Vehicles. World Electric Vehicle Journal. 2022; 13(12):221. https://doi.org/10.3390/wevj13120221

Chicago/Turabian Style

Wu, Hongchao, Huanhuan Zhang, and Yixuan Feng. 2022. "MPC-Based Obstacle Avoidance Path Tracking Control for Distributed Drive Electric Vehicles" World Electric Vehicle Journal 13, no. 12: 221. https://doi.org/10.3390/wevj13120221

Article Metrics

Back to TopTop