This paper was converted on www.awesomepapers.org from LaTeX by an anonymous user.
Want to know more? Visit the Converter page.

Planning and Tracking Control of Full Drive-by-Wire Electric Vehicles in Unstructured Scenario

Guoying Chen, Min Hua, Wei Liu, Jinhai Wang, Shunhui Song, Changsheng Liu Guoying Chen is with the State Key Laboratory of Automotive Simulation and Control, Jilin University, Changchun, 130022, P.R. China. (e-mail: [email protected]), Corresponding author.Min Hua is with the School of Engineering, University of Birmingham, Birmingham, B15 2TT, UK. (e-mail: [email protected]).Wei Liu is with the School of Electrical and Computer Engineering, Purdue University, West Lafayette, IN 47907, USA (e-mail: [email protected]).Jinhai Wang is with the School of Automotive Engineering, Wuhan University of Technology, Wuhan, 430070, P.R. China (e-mail: [email protected]).Shunhui Song is with the School of Automotive Studies, Tongji University, Shanghai, 218074, P.R. China (e-mail: [email protected]).Changsheng Liu is with the College of Computer Science and Technology, Zhejiang University, Hangzhou, 310027, P.R. China. (e-mail: [email protected]).
Abstract

Full drive-by-wire electric vehicles (FDWEV) with X-by-wire technology can achieve independent driving, braking, and steering of each wheel, providing a good application platform for autonomous driving technology. Path planning and tracking control, in particular, are critical components of autonomous driving. However, It is challenging to comprehensively design an robust control algorithm by integrating vehicle path planning in a complicated unstructured scenario for FDWEV. To address the above issue, this paper first proposes the artificial potential field (APF) method for path planning in the prescribed park with different static obstacles to generate the reference path information, where speed planning is incorporated considering kinematics and dynamic constraints. Second, two tracking control methods, curvature calculation (CC-based) and model predictive control (MPC-based) methods with the lateral dynamics model, are proposed to track the desired path under different driving conditions, in which a forward-looking behavior model of the driver with variable preview distance is designed based on fuzzy control theory. CarSim-AMESim-Simulink co-simulation is conducted with the existence of obstacles. The simulation results show that the proposed two control approaches are effective for many driving scenarios and the MPC-based path-tracking controller enhances dynamic tracking performance and ensures good maneuverability under high-dynamic driving conditions.

Index Terms:
Full drive-by-wire electric vehicles, path planning, tracking control, curvature calculation, model predictive control

I Introduction

Vehicle driving safety has always been an important research field for vehicle manufacturing [1, 2, 3, 4]. With the increasingly intelligent, electrified, wire-controlled, and networked vehicles [5], the intelligent full drive-by-wire electric vehicle possesses more advantages than traditional vehicles, such as independent driving, braking, and steering control [6, 7]. In addition, each wheel in the steering system can achieve positive and negative 180-degree rotation around the z-axis of the tire for various steering modes, e.g., crab, traverse, diagonal travel, and steer in place [8]. Controllable degrees of freedom can improve the mobility and flexibility of the vehicle at low speeds to achieve automatic parking and other functions in low-speed and narrow spaces, as well as the stability and safety of the vehicle when driving at high speeds [9]. Furthermore, due to the application of X-by-wire technology, four-wheel motor torque, and other parameters can be obtained in real time, which will provide accurate information for the advanced dynamics control system and the intelligent chassis integration control. With the introduction of the additional sensing signals and position information, the lane change, overtaking and car-following, and a series of autonomous operations will be achieved [10].

Autonomous driving(AD) integrates the information from the surroundings and the vehicle’s states via advanced sensing systems (e.g., LIDAR, cameras, GPS, and IMU) [11, 12, 13, 14, 15], and communication networks [16] to replace or assist the driver. In the last decade, with the development and advances in sensors and computer technologies, AD-related research have become hot topics in both path planning and autonomous tracking control, and have been conducted to ensure vehicle safety, comfort, and energy efficiency [17, 18].

Many studies have been dedicated to solving the collision-free path planning problem to meet the constraints of collision avoidance, steering speed, and road curvature under continuous conditions [19]. State lattice is a graph theory-based approach that has emerged in recent years, where kinematic and dynamical constraints can be regarded through state space rules and repeatable sampling in autonomous driving. Furthermore, unstructured road environments give more possibilities for employing this method. Lattice edges are computed offline to achieve real-time online planning using look-up tables to reduce the computational burden. However, several problems exist for urban areas with highly variable structured environments, such as the discretization of heading angles that may lead to oscillations between two oriented samples [20, 21]. A spline-based search tree utilizes a search tree to generate a path that is tangent to all objects and assumes that the optimal path is oriented straight ahead or touches at least one object. Each path segment from one object to the next is defined by a constant acceleration, which is effective in certain scenarios. However, transient lateral acceleration and sudden changes make this approach infeasible for vehicle robust control [22]. Alternatively, model predictive control (MPC) [23] has been widely applied in the field of automotive, where the optimization goal is to find the optimal value of a series of curvature changes to minimize the steering effort defined by the road curvature in a collision scenario, along a prediction domain from a fixed sampling time [24]. A potential field-based path planner is presented to provide obstacle avoidance with an adaptive multi-speed scheduler using a fuzzy system [25]. In [26], a time-horizon based MPC method is proposed to reduce the calculation load of vehicle speed predictive control. And the performance is verified through real road simulation experiments.

Nowadays, the vehicle models adopted for autonomous tracking control are divided into three types: geometric, kinematic, and dynamic. The mainstream control algorithms include PID control, sliding mode control (SMC), neural network control, and MPC [27] to obtain the corresponding control parameters: the steering wheel angle, throttle opening, and braking strength [28]. There is a certain delay in the actual vehicle control when executing the control command immediately, which is the biggest problem of PID algorithm in autonomous control [29]; in addition, advanced control algorithms, such as SMC and neural networks, are also widely employed [30, 31]. However, these algorithms greatly depend on parameter sensitivities and environment information, and different vehicle constraints need to be considered when the vehicle model is embedded; there are great limitations for these optimization algorithms with constraints, although MPC is capable of solving the constraints problem with high computation cost. Therefore, various tracking control algorithms need to be traded off in all aspects. The main challenge with current tracking control algorithms is a reasonable simplification of the vehicle dynamics modeling to improve the real-time performance of the algorithm while ensuring tracking accuracy.

Unfortunately, most algorithms mainly attempt to find collision-free paths with no guarantee of feasibility in the real world due to poor quality and small turns. To mitigate the above limitations in the harsh condition, in this paper, a complicated path with considerable curvatures will be created, and the precise and independent control of four-wheel angles and motor torque can be fully utilized to achieve obstacle-avoiding tracking control based on the multi-degree-of-freedom control platform of the FDWEV [32]. The autonomous tracking control of the FDWEV can provide a theoretical and practical basis for developing AD technology. The main contribution of this paper is fourfold.

1) Artificial potential field (APF) for path planning through comprehensive comparison is optimized to address the potential unreachable and local optimal problems with the improved repulsive force function and the direction of repulsive force.

2) For the high maneuverability of the FDWEV, the relevant kinematics and dynamic constraints are considered to be integrated into the vehicle speed planning. Then interpolation and piecewise fitting are conducted to provide achievable position information for tracking control.

3) Based on fuzzy control theory, a forward-looking driver behavior model with variable preview distance is designed. The curvature calculation is proposed based on the vehicle lateral dynamics and kinematic models. For the shortcoming of the tracking control algorithm based on curvature calculation, the MPC algorithm is designed by considering the vehicle constraints, real-time prediction, and feedback optimization of the vehicle states.

4) Based on the path planning and vehicle speed planning in the prescribed park, the autonomous tracking controls are verified based on the co-simulation of Simulink/Carsim/Amesim platform under different conditions with speeds of 30 km/h and 50 km/h in a harsh environment with considerable curvatures.

The rest of this paper is organized as follows: Section 2 formulates the lateral dynamics model. In section 3, path planning with APF method is proposed with the generated reachable points of vehicle tracking control. In Section 4, tracking control based on the curvature method and MPC algorithm are proposed according to the kinematic and dynamics model. Section 5 conducts simulation experiments and analyzes the results for validation and evaluation, followed by the conclusions in Section 6.

II Lateral dynamics model

The lateral dynamics model is established firstly to design the tracking controller. The global coordinate system XY and the vehicle coordinate system xy are defined as shown in Fig. 1.

Refer to caption

Figure 1: Schematic diagram for lateral dynamics model.

In detail, x is along the vehicle’s longitudinal direction, and y is along the lateral direction, a fixed coordinate system xyx^{\prime}y^{\prime} is defined, where xx^{\prime} is defined in the direction of the tangential velocity V and yy^{\prime} is pointing at the rotation center O of the vehicle from the position of the mass center c.g of the vehicle; the yaw angle of the x-direction of the vehicle coordinate system with respect to the global X-axis direction is denoted by the φ\varphi; V is the tangential velocity of the vehicle, and VxV_{x} (called longitudinal velocity) is set as the x-axis component of V; δf\delta_{f} is the front wheel steering angle, φdes\varphi_{des} is the desired yaw angle of the vehicle, and Δφ\Delta\varphi is the yaw angle deviation with respect to the desired path. In addition, the lateral position error from the vehicle center of mass along the y-direction to the corresponding desired path point is Δy\Delta y, Δy\Delta y, also known as the current deviation [33]. Assuming that the desired path has a constant curvature and the vehicle has a constant speed in the longitudinal direction. Based on the two-degree-of-freedom model derived above, the lateral motion control at a constant speed y¨=V˙y,y˙=Vy\ddot{y}=\dot{V}_{y},\dot{y}=V_{y}, are expressed as follows:

y¨=(Cf+CrVxm)y˙+(VxCflfCrlrVxm)φ˙+Cfmδf\ddot{y}=-(\frac{C_{f}+C_{r}}{V_{x}m})\dot{y}+(-V_{x}-\frac{C_{f}l_{f}-C_{r}l_{r}}{V_{x}m})\dot{\varphi}+\frac{C_{f}}{m}\delta_{f} (1)
φ¨=(CflfCrlrIzVx)y˙(Cflf2+Crlr2IzVx)φ˙+CflfIzδf\ddot{\varphi}=-(\frac{C_{f}l_{f}-C_{r}l_{r}}{I_{z}V_{x}})\dot{y}-(\frac{C_{f}l_{f}^{2}+C_{r}l_{r}^{2}}{I_{z}V_{x}})\dot{\varphi}+\frac{C_{f}l_{f}}{I_{z}}\delta_{f} (2)
Δφ=φdesφ\Delta\varphi=\varphi_{des}-\varphi (3)
Δ˙φ=φ˙desφ˙\dot{\Delta}\varphi=\dot{\varphi}_{des}-\dot{\varphi} (4)
Δ˙y=y˙+VxΔφ\dot{\Delta}y=-\dot{y}+V_{x}\Delta{\varphi} (5)

The preview deviation yL2y_{L2} is the lateral position deviation of the vehicle at the effective preview distance LeffL_{eff} from the vehicle center of mass, as shown in Fig. 1. The preview deviation yL2y_{L2} can be considered as the sum of three different distances, which is expressed as follows:

yL2=ΔyL2+Δy+Leffsin(Δφ)y_{L2}=\Delta y_{L2}+\Delta y+L_{eff}\sin(\Delta\varphi) (6)

where Δy\Delta y is the current lateral deviation, Δφ\Delta\varphi is the heading angle error, and φ\varphi is the yaw rate. And the only variable yL2y_{L2} depends on the change of the future path. The current lateral position deviation Δy\Delta y depends on the current lateral position of the vehicle, and the third term of Eq. (6) depends on the heading angle of the path and the current heading angle of the vehicle. For small angles Δφ\Delta\varphi, the above equation can be approximated as:

yL2ΔyL2+Δy+Leffsin(Δφ)y_{L2}\approx\Delta y_{L2}+\Delta y+L_{eff}\sin(\Delta\varphi) (7)

To calculate the preview deviation precisely, it is necessary to find the relationship between the variable yL2y_{L2} and the other variables. If the vehicle travels with a constant tangential velocity VV on a circular path with radius RR, the relationship with the ideal yaw rate φ˙des\dot{\varphi}_{des} is expressed as:

φ˙des=VR\dot{\varphi}_{des}=\frac{V}{R} (8)

It can also be seen from Fig. 1 that the relationship between the radius of RR and the effective preview distance LeffL_{eff} is:

sin(2θ)=LeffR\sin(2\theta)=\frac{L_{eff}}{R} (9)

Where θ\theta is the angle between the current driving direction of the vehicle and the point (Leff,ΔyL2)(L_{eff},\Delta y^{\prime}_{L2}) defined in the coordinate system xyx^{\prime}y^{\prime}. When combining Eq. (8) and Eq. (9) and θ=αtan(ΔyL2Leff)\theta=\alpha\tan(\frac{\Delta y^{\prime}_{L2}}{L_{eff}}) (as can be seen in Fig. 1), the following relationship is derived as follows:

φ˙des=Vsin(2θ)Leff=Vsin(2αtan(ΔyL2/Leff))Leff2VΔyL2Leff2\begin{split}\dot{\varphi}_{des}&=\frac{V\sin(2\theta)}{L_{eff}}\\ &=\frac{V\sin(2\cdot\alpha\tan(\Delta y^{\prime}_{L2}/L_{eff}))}{L_{eff}}\\ &\approx\frac{2V\Delta y^{\prime}_{L2}}{L^{2}_{eff}}\end{split} (10)

Then

ΔyL2Leff2φ˙des2V\Delta y^{\prime}_{L2}\approx\frac{L^{2}_{eff}\dot{\varphi}_{des}}{2V} (11)

where the distance ΔyL2\Delta y^{\prime}_{L2} is not equal to ΔyL2\Delta y_{L2}, since there is the lateral angle α\alpha between the driving direction of the vehicle body and the movement direction of the actual wheels due to the side slip. Therefore, it can be approximated as follows:

ΔyL2ΔyL2Lefftan(α)\Delta y^{\prime}_{L2}\approx\Delta y_{L2}-L_{eff}\tan(\alpha) (12)

As for the small side slip, the lateral angle α\alpha can be expressed as:

αtan(α)=dydx=dydtdtdx=y˙Vx\alpha\approx\tan(\alpha)=\frac{\mathrm{d}y}{\mathrm{d}x}=\frac{\mathrm{d}y}{\mathrm{d}t}\cdot\frac{\mathrm{d}t}{\mathrm{d}x}=\frac{\dot{y}}{V_{x}} (13)

In addition, the preview deviation yL2y_{L2} needs to be compensated for the side slip. The compensated preview deviation is described as:

ΔyL2SlipcompΔyL2Leffy˙VxΔyL2y˙δfVxLeffδfΔyL2βLeffδf\begin{split}\Delta y_{L2Slipcomp}&\approx\Delta y_{L2}-L_{eff}\cdot\frac{\dot{y}}{V_{x}}\\ &\approx\Delta y_{L2}-\frac{\dot{y}}{\delta_{f}V_{x}}L_{eff}\cdot\delta_{f}\\ &\approx\Delta y_{L2}-\beta\cdot L_{eff}\cdot\delta_{f}\end{split} (14)
β=Gδf,y˙(0,Vx)=y˙δfVx=CfVx(lfmVx2+CrLr2+Crlflr)CfmVx2lf+CrmVx2lr+CfCrlf2+2CfCrlflr+CfCrlr2\begin{split}&\beta=G_{\delta_{f},\dot{y}}(0,V_{x})=\frac{\dot{y}}{\delta_{f}V_{x}}\\ &=\frac{C_{f}V_{x}(-l_{f}mV^{2}_{x}+C_{r}L^{2}_{r}+C_{r}l_{f}l_{r})}{-C_{f}mV^{2}_{x}l_{f}+C_{r}mV^{2}_{x}l_{r}+C_{f}C_{r}l^{2}_{f}+2C_{f}C_{r}l_{f}l_{r}+C_{f}C_{r}l^{2}_{r}}\end{split} (15)

When the vehicle is in steady state y¨=0,φ¨=0\ddot{y}=0,\ddot{\varphi}=0, the gain of the above equation can be derived based on the two-freedom model and the expression for the preview deviation considering the vehicle side slip can be obtained as:

yL2Slipcomp=ΔyL2Slipcomp+Δy+LeffΔφ=Leff2φ˙des2VβLeffδf+Δy+LeffΔφ\begin{split}&y_{L2Slipcomp}=\Delta y_{L2Slipcomp}+\Delta y+L_{eff}\Delta\varphi\\ &=\frac{L^{2}_{eff}\dot{\varphi}_{des}}{2V}-\beta\cdot L_{eff}\cdot\delta_{f}+\Delta y+L_{eff}\Delta\varphi\end{split} (16)

The current lateral deviation Δy\Delta y, the lateral velocity yy, the yaw angle deviation Δφ\Delta\varphi, and the yaw rate φ\varphi are set as the state variables xx; the input variables uu are the front wheel angle δf\delta_{f} and the desired yaw rate φdes\varphi_{des}, and then the output variables are current lateral deviation Δy\Delta y, the yaw angle deviation Δφ\Delta\varphi, and the preview deviation yL2slipcompy_{L2slipcomp} considering vehicle side slip. Assuming VVxV\approx V_{x}. Thus, the states equations can be described as follows:

ddt[Δyy˙Δφφ˙]=[01Vx00Cf+CrVxm0VxCflfCrlrVxm00010CflfCrlrIzVx0Cflf2+Crlr2IzVx][Δyy˙Δφφ˙]+[00Cfm001CflfIz0][δfφ˙des]\begin{split}&\frac{\mathrm{d}}{\mathrm{d}t}\begin{bmatrix}&\Delta y\\ &\dot{y}\\ &\Delta\varphi\\ &\dot{\varphi}\end{bmatrix}\\ &=\begin{bmatrix}&0&-1&V_{x}&0\\ &0&-\frac{C_{f}+C_{r}}{V_{x}m}&0&-V_{x}-\frac{C_{f}l_{f}-C_{r}l_{r}}{V_{x}m}\\ &0&0&0&-1\\ &0&-\frac{C_{f}l_{f}-C_{r}l_{r}}{I_{z}V_{x}}&0&-\frac{C_{f}l^{2}_{f}+C_{r}l^{2}_{r}}{I_{z}V_{x}}\end{bmatrix}\begin{bmatrix}&\Delta y\\ &\dot{y}\\ &\Delta\varphi\\ &\dot{\varphi}\end{bmatrix}\\ &+\begin{bmatrix}&0&0\\ &\frac{C_{f}}{m}&0\\ &0&1\\ &\frac{C_{f}l_{f}}{I_{z}}&0\end{bmatrix}\begin{bmatrix}&\delta_{f}\\ &\dot{\varphi}_{des}\end{bmatrix}\end{split} (17)
[ΔyΔφyL2slipcompφ˙]=[1000001010Leff00001][Δyy˙Δφφ˙]+[0000LeffβLeff22Vx00][δfφ˙des]\begin{split}\begin{bmatrix}&\Delta y\\ &\Delta\varphi\\ &y_{L2slipcomp}\\ &\dot{\varphi}\end{bmatrix}&=\begin{bmatrix}&1&0&0&0\\ &0&0&1&0\\ &1&0&L_{eff}&0\\ &0&0&0&1\end{bmatrix}\begin{bmatrix}&\Delta y\\ &\dot{y}\\ &\Delta\varphi\\ &\dot{\varphi}\end{bmatrix}\\ &+\begin{bmatrix}&0&0\\ &0&0\\ &-L_{eff}\beta&\frac{L^{2}_{eff}}{2V_{x}}\\ &0&0\end{bmatrix}\begin{bmatrix}&\delta_{f}\\ &\dot{\varphi}_{des}\end{bmatrix}\end{split} (18)

The lateral dynamics model is established and used to design the tracking controllers, followed by path planning to provide the tracking input information.

III Path planning

This section focuses on the path planning of the FDWEV in the presence of static obstacles to provide path point information for tracking control by avoiding obstacles reasonably. Because of the varying sizes and shapes of the various barriers, it is necessary to project the obstacles onto the ground to create a two-dimensional environment. Then, an external circle is utilized to simplify the obstacles so that they fit within a circle. Within the confines of a predetermined park, the vehicle is initially simplified to drive in the form of a circle, with the origin being the mass center of the vehicle. The corresponding diagram is presented in Fig. 2.

Refer to caption

Figure 2: Diagram of the simplified obstacle avoidance in a complicated unstructured scenario

III-A Path generator

The artificial potential field (APF) method is widely used for the path generator. However, it currently suffers from the local optimal solution problem and target unreachability. Based on it, some scholars have proposed some improved algorithms[34, 35]. In this paper, modifying the repulsive force function and repulsive direction have been presented.

(1) Repulsive force function optimization

When the moving vehicle, the target point, and the obstacle are all in the same line and the target point is close to the obstacle, the attractive force of the target point to the moving vehicle decreases while the repulsive force of the obstacle from the moving vehicle increases. As a result, the moving vehicle cannot reach the target point since the repulsive force does not vary as the driving vehicle gets closer to the target point in this scenario. Therefore, modifying the repulsive force function decreases the repulsive force as the moving vehicle gets closer to the target point. In this way, the repulsive and the attractive force are equal to zero at the target point, and the vehicle can maintain the target point. The improved repulsive field function is described as follows:

Urep,j={12ηj(1dj(x)1Qj)2d2(x,xgoal)dj(x)Qj0dj(x)>QjU_{rep,j}=\left\{\begin{aligned} &\frac{1}{2}\eta_{j}(\frac{1}{d_{j}(x)}-\frac{1}{Q^{*}_{j}})^{2}d^{2}(x,x_{goal})&d_{j}(x)\leq Q^{*}_{j}\\ &0&d_{j}(x)>Q^{*}_{j}\end{aligned}\right. (19)

where Urep,jU_{rep,j} denotes the improved repulsive force function, ηj\eta_{j} is the coefficient constant of the repulsive force function. dj(x)d_{j}(x) is the shortest distance between the moving vehicle and the jthj_{th} obstacle. QjQ^{*}_{j} is the maximum range of the influence for jthj_{th} obstacle on the moving vehicle. When the shortest distance between the moving vehicle and the obstacle is less than QjQ^{*}_{j}, the repulsive force function will affect the moving vehicle. d(x,xgoal)d(x,x_{goal}) denotes the shortest distance between the moving vehicle and the target point.

The corresponding repulsive force function is:

Frep=grad(Urep,j)={Frep1N1+Frep2N2dj(x)Qj0dj(x)>QjF_{rep}=-grad(U_{rep,j})=\left\{\begin{aligned} &F_{rep1}N_{1}+F_{rep2}N_{2}&d_{j}(x)\leq Q^{*}_{j}\\ &0&d_{j}(x)>Q^{*}_{j}\end{aligned}\right. (20)

where:

Frep1=ηj(1dj(x)1Qj)d2(x,xgoal)dj2(x)F_{rep1}=\eta_{j}(\frac{1}{\mathrm{d}_{j}(x)}-\frac{1}{Q^{*}_{j}})\frac{\mathrm{d}^{2}(x,x_{goal})}{\mathrm{d}^{2}_{j}(x)} (21)
Frep2=ηj(1dj(x)1Qj)2d(x,xgoal)F_{rep2}=\eta_{j}(\frac{1}{\mathrm{d}_{j}(x)}-\frac{1}{Q^{*}_{j}})^{2}\mathrm{d}(x,x_{goal}) (22)

Frep1F_{rep1} and Frep2F_{rep2} are the two splitting forces of FrepF_{rep}, where the direction of Frep1F_{rep1} is from the center of the obstacle pointing to the moving vehicle, the direction of Frep2F_{rep2} and the attractive force are the same.

This improved method incorporates an adjustment factor d(x,xgoal)\mathrm{d}(x,x_{goal}) so that the repulsive force decreases while the moving vehicle is approaching the target point. The repulsive force is zero, and the attractive force is also zero when reaching the target point.

(2) Repulsive force direction reformation

Altering the repulsive force described above is insufficient to solve either of the difficulties. As a result, based on the repulsive force function, modifying the direction of repulsive force Frep1F_{rep1} has been conducted. Frep1F_{rep1} and Frep2F_{rep2} are the two splitting forces of the repulsive force, and the direction of Frep1F_{rep1} is from the obstacle to the moving vehicle, and the direction of Frep2F_{rep2} is from the moving vehicle to the target point. When the angle between Frep2F_{rep2} and the attractive force is larger than 9090^{\circ}, this may nevertheless result in a locally optimal solution. Therefore, modifying the direction of the repulsive force is to define Frep1F_{rep1} as a tangent direction along the influencing range of the obstacle and the angle between it and the attractive force, which is less than or equal to 9090^{\circ}.

III-B Speed planning

(1) Vehicle dynamics constraints

According to the vehicle dynamics theory analysis, the under-steering gain can be defined as K=m(lf+lr)2(lfCαrlrCαf)K=\frac{m}{(l_{f}+l_{r})^{2}}(\frac{l_{f}}{C_{\alpha r}}-\frac{l_{r}}{C_{\alpha f}}). Then, steering gain is the ratio of the yaw rate to the front wheel angle, which is φδf=Vx/(lf+lr)1+KVx2\frac{\varphi}{\delta_{f}}=\frac{V_{x}/(l_{f}+l_{r})}{1+KV^{2}_{x}}, ensuring the vehicle’s stability and safety.[36].

{φ˙δ=Vxlf+lrVx=φ˙R\left\{\begin{aligned} &\frac{\dot{\varphi}}{\delta}=\frac{V_{x}}{l_{f}+l_{r}}\\ &V_{x}=\dot{\varphi}R\end{aligned}\right. (23)

In the vehicle coordinate system, the vehicle lateral acceleration can be expressed as:

αy=limΔt0ΔVy+VxΔθΔt\alpha_{y}=\lim_{\Delta t\to 0}\frac{\Delta V_{y}+V_{x}\cdot\Delta\theta}{\Delta t} (24)

To avoid obstacles, the vehicle is steering in such a way as to satisfy steady-state steering and to make certain that the lateral side slip angle of the center of mass is as small as possible. Assuming the velocity of the vehicle along the longitudinal axis remains constant, the lateral acceleration can be represented as follows:

αy=Vx2lf+lrδ\alpha_{y}=\frac{V^{2}_{x}}{l_{f}+l_{r}}\cdot\delta (25)

To make the tires in the linear area, the lateral acceleration should be no more than 0.4 g, and the front wheel needs to be satisfied as follows:

δ0.4glf+lrVx2\delta\leq 0.4g\cdot\frac{l_{f}+l_{r}}{V^{2}_{x}} (26)

Therefore, the vehicle’s steering would be simultaneously impacted by the velocity and steering radius. And the front wheel steering angle should meet smoothly and securely:

δ=min(0.4glf+lrVx2,lf+lrRmin)\delta=\min(0.4g\cdot\frac{l_{f}+l_{r}}{V^{2}_{x}},\frac{l_{f}+l_{r}}{R_{\min}}) (27)

During steering, the longitudinal speed is far too high to have any impact on the safety of the vehicle, and the vehicle speed at any given curve can be satisfied:

Vlim=gμ/ρdV_{\lim}=\sqrt{g\mu/\rho_{d}} (28)

Eq. 28 the limited speed under ideal conditions, it is required to adjust the vehicle speed by inserting an adjustment factor λd\lambda_{d} by considering the real instantaneous scenario:

Vlim=λdgμ/ρdV_{\lim}=\lambda_{d}\sqrt{g\mu/\rho_{d}} (29)

It can be seen that the only factors that influence the limited speed are the radius of the road, denoted by λd\lambda_{d}, and the maximum adhesion coefficient, denoted by μ\mu. Then the longitudinal reference speed should also consider the maximum legal speed restriction. Therefore, the following can be obtained[37] :

Vref=min(Vset,Vlim)V_{ref}=\min(V_{set},V_{\lim}) (30)

where VsetV_{set} is the desired target speed.

(2) Vehicle kinematic constraints

The front wheels need to be in accordance with the ideal Ackermann geometry steering, and the vehicle kinematic model can be described as follows.

{X˙=VsinθY˙=Vcosθθ=Vtanδflf+lr\left\{\begin{aligned} &\dot{X}=V\sin\theta\\ &\dot{Y}=V\cos\theta\\ &\theta=\frac{V\tan\delta_{f}}{l_{f}+l_{r}}\end{aligned}\right. (31)

The incomplete constraint can be expressed as:

{X˙=X˙sinθY˙cosθY˙=X˙sin(δf+θ)Y˙cos(δf+θ)(lf+lr)θcosδf\left\{\begin{aligned} &\dot{X}=\dot{X}\sin\theta-\dot{Y}\cos\theta\\ &\dot{Y}=\dot{X}\sin(\delta_{f}+\theta)-\dot{Y}\cos(\delta_{f}+\theta)-(l_{f}+l_{r})\theta\cos\delta_{f}\end{aligned}\right. (32)

where θ\theta is the angle between the vehicle and the X-axis direction. Based on the above constraints, it is clear that the kinematic constraints include a speed limit VlimV_{\lim} without side slip, with different curvatures:

Vlim=μg(1+(lf+lr)2ρd2)R2(lf+lr)2ρd=1R\begin{split}&V_{\lim}=\sqrt{\mu g\sqrt{(1+(l_{f}+l_{r})^{2}\rho^{2}_{d})}\cdot\sqrt{R^{2}-(l_{f}+l_{r})^{2}}}\\ &\rho_{d}=\frac{1}{R}\end{split} (33)

The reference speed VrefV_{ref} will be selected as the smallest speed value.

IV Tracking control

The tracking control algorithms are designed to accurately follow the path and the corresponding vehicle speed to avoid static obstacles. Firstly, the fuzzy control is used to obtain the preview time, combined with speed planning to get the variable preview distance. Furthermore, the vehicle kinematics and dynamics models are considered respectively with vehicle constraints. Thus, a tracking control model based on curvature calculation (CC-based) and model prediction control (MPC-based) methods are established.

IV-A Design of tracking controller based on curvature calculation

In the lateral dynamics model, the defined preview deviation yL2y_{L2} contains three parts, ΔyL2\Delta y_{L2} indicating the future path change, Δy\Delta y representing the current lateral position deviation, and Δφ\Delta\varphi indicating the current heading angle deviation.

(1) Curvature calculation based on current lateral deviation Δy\Delta y

To calculate and correct the deviation between the current path and the reference path, PID controllers, as the most common feedback controllers used in industrial fields, were first employed due to no representation of the internal system and the straightforward application to determine the ideal curvature κΔy\kappa_{\Delta y} based on the present deviance. The following is an equation representing the PID controller.

κΔy(k)=KpΔy(k)+Kij=0kΔy(j)+Kd[Δy(k)Δy(k1)]\kappa_{\Delta y}(k)=K_{p}\Delta y(k)+K_{i}\sum_{j=0}^{k}\Delta y(j)+K_{d}[\Delta y(k)-\Delta y(k-1)] (34)

The KpK_{p} is the proportional coefficient, the KiK_{i} is the integral coefficient, and the KdK_{d} is the differential coefficient. The I controller provides the most effective results by modifying the three parameters in the repeated simulations. As a result, the I controller is used to determine the ideal curvature. Then, the sensor measurement has a certain delay in the real-world case, which results in a delay in the acquired current lateral deviation Δy\Delta y. So a delayed module esTDelaye^{sT_{Delay}} needs to be introduced to provide a more accurate control in Fig. 3.

Refer to caption

Figure 3: Block diagram of the current deviation control loop

(2) Curvature calculation based on preview deviation yL2y_{L2}

For the control loop of the yL2y_{L2}, the data delay is first considered to get the delayed preview deviation yL2delayedy_{L2delayed}, and then the derivation from the lateral dynamics model is given:

φ˙des=Vsin(2θ)Leff2VΔyL2Le2ff\begin{split}&\dot{\varphi}_{des}=\frac{V\sin\left(2\theta\right)}{L_{e}ff}\approx\frac{2V{\Delta y{}^{\prime}}_{L2}}{L^{2}_{e}ff}\end{split} (35)

The preview deviation distance can therefore be converted into the ideal curvature as shown below:

κyL2=φ˙desVx2ΔyL2Le2ff\begin{split}&\kappa_{y_{L2}}=\frac{\dot{\varphi}_{des}}{V_{x}}\approx\frac{2{\Delta y_{L2}}}{L^{2}_{e}ff}\end{split} (36)

The conversion of the preview deviation into the corresponding curvature value by gain 2/Le2ff2/{L^{2}_{e}ff} is conducted. Then a parameter GoutG_{out} can be added between the two distances, the range of which is set to 0<Gout<10<G_{out}<1 to make the steering less aggressive. Since the vehicle is subject to side slip, a compensation amount is considered to calculate the preview distance deviation to obtain yL2slipcompy_{L2_{slipcomp}}, which is:

yL2slipcomp=yL2dydxLeff\begin{split}&y_{L2_{slipcomp}}=y_{L2}-\frac{dy}{dx}{L_{e}ff}\end{split} (37)

where

dydx=dydtdtdx=y˙δwheel1Vxδf=Gδwheel,y˙(0,Vx)VxδsteeringwheelSteerRatio\begin{split}&\frac{dy}{dx}=\frac{dy}{dt}\frac{dt}{dx}=\frac{\dot{y}}{\delta_{wheel}}\frac{1}{V_{x}}\delta_{f}=\frac{G_{\delta_{wheel},\dot{y}}(0,V_{x})}{V_{x}}\frac{\delta_{steeringwheel}}{SteerRatio}\end{split} (38)

The compensated preview distance deviation is brought into the curvature calculation module as the actual preview deviation, which is yL2slipcomp=yL2y_{L2_{slipcomp}}=y_{L2}. The control block diagram can be obtained as shown in Fig. 4.

Refer to caption

Figure 4: Block diagram of the preview deviation control loop

Finally, the ideal curvature κΔy\kappa_{\Delta y} based on the current deviation and the ideal curvature κyL2\kappa_{y_{L2}} based on the preview distance are transformed into the corresponding steering angle in different cases, the conversion between the steering angle and the ideal curvature is derived as follows:

Gcurvature,δf(0,Vx)=δfκ=δfVxφ˙=Gδf,Ψ˙1(0,Vx)Vx=CfmVx2lf+CrmVx2lr+CfCrlf2+2CfCrlflr+CfCrlr2CfCrVx(lf+lr)Vx=CfmVx2lf+CrmVx2lr+CfCrlf2+2CfCrlflr+CfCrlr2CfCr(lf+lr)\begin{split}&G_{curvature,\delta_{f}}(0,V_{x})=\frac{\delta_{f}}{\kappa}=\frac{\delta_{f}V_{x}}{\dot{\varphi}}=G^{-1}_{\delta_{f,\dot{\Psi}}}(0,V_{x})\cdot V_{x}\\ &=\frac{-C_{f}mV^{2}_{x}l_{f}+C_{r}mV^{2}_{x}l_{r}+C_{f}C_{r}l^{2}_{f}+2C_{f}C_{r}l_{f}l_{r}+C_{f}C_{r}l^{2}_{r}}{C_{f}C_{r}V_{x}(l_{f}+l_{r})}V_{x}\\ &=\frac{-C_{f}mV^{2}_{x}l_{f}+C_{r}mV^{2}_{x}l_{r}+C_{f}C_{r}l^{2}_{f}+2C_{f}C_{r}l_{f}l_{r}+C_{f}C_{r}l^{2}_{r}}{C_{f}C_{r}(l_{f}+l_{r})}\end{split} (39)

The effective preview time can be obtained from the fuzzy controller and the speed limit obtained from the vehicle dynamics and kinematics. An effective preview distance can be obtained by multiplying the speed with the effective preview time. The CC-based tracking controller framework can therefore be obtained as shown in Fig. 5. GoutG_{out} is an adaptive parameter, and LocalOffsetLimitLocalOffsetLimit is set to 0.2m, and the logic pseudo-code for the judgment is:

Algorithm 1 The logic pseudo-code for the judgment
  if ALatLimit0.4gALatLimit\leq 0.4g then
     Gout=0.8G_{out}=0.8
  else
     Gout=0.65G_{out}=0.65
  end if
  if |Δy|>LocalOffsetLimit\left|\Delta y\right|>LocalOffsetLimit then
     DisableLocalOffsetIntegrator=TrueDisableLocalOffsetIntegrator=True
  else
     DisableLocalOffsetIntegrator=FalseDisableLocalOffsetIntegrator=False
  end if

Refer to caption

Figure 5: Block diagram of CC-based control strategy design

IV-B Design of tracking controller based on model predictive control

(1) Optimization objectives

The aim is not only to require the vehicle to produce the smallest lateral deviation but also to achieve the smallest steering wheel angle variation based on the consideration of the stability and safety [38, 39]. Therefore, the optimization objective function is defined as follows:

V(k)=i=1Hpz(k+i|k)r(k+i)Q(i)2+i=1Hpu(k+i|k)Ru(i)2+i=1HpΔu(k+i|k)Q(i)2\begin{split}V(k)&=\sum_{i=1}^{H_{p}}\left\|z(k+i|k)-r(k+i)\right\|^{2}_{Q(i)}\\ &+\sum_{i=1}^{H_{p}}\left\|u(k+i|k)\right\|^{2}_{R_{u}(i)}+\sum_{i=1}^{H_{p}}\left\|\Delta u(k+i|k)\right\|^{2}_{Q(i)}\end{split} (40)

The reference path information is defined as:

R(k)=[r(k+1|k)r(k+Hp|k)]TR(k)=\left[r(k+1|k)\cdots r(k+H_{p}|k)\right]^{T} (41)

Normalization is required due to different magnitudes of three terms for the objective function; then the objective function can be expressed as:

V(k)=Z(k)R(k)Q2+U(k)Ru2+ΔU(k)R2V(k)=\left\|Z(k)-R(k)\right\|^{2}_{Q}+\left\|U(k)\right\|^{2}_{R_{u}}+\left\|\Delta U(k)\right\|^{2}_{R} (42)

The vehicle lateral tracking deviation is defined as:

ε(k)=R(k)Hx(k)Pu(k1)\varepsilon(k)=R(k)-Hx(k)-Pu(k-1) (43)

Bring the lateral tracking deviation into the objective function as follows:

V(k)=SΔU(k)ε(k)Q2+U(k)Ru2+ΔU(k)R2=[ΔU(k)TSTε(k)T]Q[SΔU(k)ε(k)]+[u(k1)TΓT+Δu(k)TΛT]Ru[Γu(k1)+ΛΔu(k)]+ΔU(k)TRΔU(K)\begin{split}V(k)&=\left\|S\Delta U(k)-\varepsilon(k)\right\|^{2}_{Q}+\left\|U(k)\right\|^{2}_{R_{u}}+\left\|\Delta U(k)\right\|^{2}_{R}\\ &=\left[\Delta U(k)^{T}S^{T}-\varepsilon(k)^{T}\right]Q\left[S\Delta U(k)-\varepsilon(k)\right]\\ &+\left[u(k-1)^{T}\Gamma^{T}+\Delta u(k)^{T}\Lambda^{T}\right]R_{u}\left[\Gamma u(k-1)+\Lambda\Delta u(k)\right]\\ &+\Delta U(k)^{T}R\Delta U(K)\end{split} (44)

The above equation is simplified as follows:

V(k)=CΔU(k)TM+ΔU(k)TNΔU(K)M=2STQε(k)2ΛTRuΓu(k1)N=ΛTRuΛ+R+STQS\begin{split}&V(k)=C-\Delta U(k)^{T}M+\Delta U(k)^{T}N\Delta U(K)\\ &M=2S^{T}Q\varepsilon(k)-2\Lambda^{T}R_{u}\Gamma u(k-1)\\ &N=\Lambda^{T}R_{u}\Lambda+R+S^{T}QS\end{split} (45)

It is easy to see that M and N are irrelevant to ΔU(k)\Delta U(k). Then the dimensions of the input, output, and state variables in the system are assumed to be l, m, and n; therefore, the dimensions of the matrix can be obtained as shown in Table 1.

TABLE I: Table of Matrix dimension
Matrix Dimension
Γ\Gamma lHu×llH_{u}\times l
Λ\Lambda lHu×lHulH_{u}\times lH_{u}
QQ mHp×mHpmH_{p}\times mH_{p}
RuR_{u} lHu×lHulH_{u}\times lH_{u}
RR lHu×lHulH_{u}\times lH_{u}
HH mHp×nmH_{p}\times n
PP mHp×lmH_{p}\times l
SS mHp×lHumH_{p}\times lH_{u}
ε\varepsilon m×1m\times 1
MM lHu×1lH_{u}\times 1
NN lHu×lHulH_{u}\times lH_{u}

(2) Constraints

To ensure the safety and stability of the vehicle, limitations on the steering wheel angle, steering wheel angle rate, lateral acceleration, lateral deviation, and actuator capacity should be considered when designing the control algorithms. Firstly, the constraint of the front wheel angle as the model input is set as 2525-25^{\circ}-25^{\circ}, which is the extreme value of the steering angle. Thus, the constraints on the front wheel angle and the corresponding variation are designed as follows:

25δf25-25^{\circ}\leq\delta_{f}\leq 25^{\circ}\\ (46)
0.47Δδf0.47-0.47^{\circ}\leq\Delta\delta_{f}\leq 0.47^{\circ} (47)

Then the lateral acceleration is αyμg\alpha_{y}\leq\mu g in the theoretical case, and this paper sets the limit as αy0.85μg\alpha_{y}\leq 0.85\mu g for safety. The yaw rate can also be obtained as follows:

ψVx0.85μgψ˙0.85μgVx\begin{split}&\psi\cdot V_{x}\leq 0.85\mu g\\ &\dot{\psi}\leq\frac{0.85\mu g}{V_{x}}\end{split} (48)

Finally, the side slip angle cannot be exceeded to 55^{\circ}, within which there is a linear relationship between the lateral force and side slip angle according to the tyre characteristics. Therefore, the constraint of the side slip angle of the front wheel is:

2.5α2.5-2.5^{\circ}\leq\alpha\leq 2.5^{\circ} (49)

(3) Optimization with constraints

The above constraints can first be expressed as linear inequalities as:

E[ΔU(k)1]0E\begin{bmatrix}&\Delta U(k)\\ &1\end{bmatrix}\leq 0 (50)
F[U(k)1]0F\begin{bmatrix}&U(k)\\ &1\end{bmatrix}\leq 0 (51)
G[Z(k)1]0G\begin{bmatrix}&Z(k)\\ &1\end{bmatrix}\leq 0 (52)

where the matrix FF is denoted as f=[F1,F2,,FHu,f]f=[F_{1},F_{2},\cdots,F_{H_{u}},f], FiF_{i} is the matrix of q×mq\times m, ff is the matrix of q×1q\times 1, it can be described as:

i=1HuFiu(k+i1|k)+f0\sum_{i=1}^{H_{u}}F_{i}u(k+i-1|k)+f\leq 0 (53)

Because

u(k+i1|k)=u(k1)+j=1i1Δu(k+j|k)u(k+i-1|k)=u(k-1)+\sum_{j=1}^{i-1}\Delta u(k+j|k) (54)

Bring this equation into Eq. (53):

j=1HuFjΔu(k|k)+j=2HuFjΔu(k+2|k)++FHuΔu(k+Hu1|k)+j=1HuFju(k1)+f0\begin{split}&\sum_{j=1}^{H_{u}}F_{j}\Delta u(k|k)+\sum_{j=2}^{H_{u}}F_{j}\Delta u(k+2|k)+\cdots\\ &+F_{H_{u}}\Delta u(k+H_{u}-1|k)+\sum_{j=1}^{H_{u}}F_{j}u(k-1)+f\leq 0\end{split} (55)

where Fi=j=1HuFjF_{i}=\sum_{j=1}^{H_{u}}F_{j}

FΔU(k)F1u(k1)fF\Delta U(k)\leq-F_{1}u(k-1)-f (56)

Thus Eq. (51) can be transformed into a linear constraint on ΔU(k)\Delta U(k). Similarly, Eq. (52) can be transformed into a constraint on ΔU(k)\Delta U(k).

G[Hx(k|k)+Pu(k1)+SΔU(K)1]0G\begin{bmatrix}&Hx(k|k)+Pu(k-1)+S\Delta U(K)\\ &1\end{bmatrix}\leq 0 (57)

where G=[T,g]G=[T,g], gg is the last column of GG, since it is obtained:

T[Hx(k|k)+Pu(k1)]+TSΔU(k)+g0T\left[Hx(k|k)+Pu(k-1)\right]+TS\Delta U(k)+g\leq 0 (58)

Furthermore, it can be described as:

TSΔU(k)T[Hx(k|k)+Pu(k1)]gTS\Delta U(k)\leq-T\left[Hx(k|k)+Pu(k-1)\right]-g (59)

Finally, it can be summarized as:

WΔU(k)wW\Delta U(k)\leq w (60)

Combining with three equations, it can be described as:

[ETSW]ΔU(k)[E1u(k1)eT[Hx(k|k)+Pu(k1)]gw]\begin{bmatrix}&E\\ &TS\\ &W\end{bmatrix}\Delta U(k)\leq\begin{bmatrix}&-E_{1}u(k-1)-e\\ &-T\left[Hx(k|k)+Pu(k-1)\right]-g\\ &w\end{bmatrix} (61)

Thus, the optimization problem can be expressed as follows:

minΔU(k)TM+ΔU(k)TNΔU(k)subλΔU(k)κ\begin{split}min\qquad&-\Delta U(k)^{T}M+\Delta U(k)^{T}N\Delta U(k)\\ &sub\qquad\lambda\Delta U(k)\leq\kappa\end{split} (62)

The optimization solution is obtained by solving the gradient function for the objective function and making it equal to 0.

ΔU(k)V=M+2NΔU(k)=0\nabla_{\Delta U(k)}V=-M+2N\Delta U(k)=0 (63)

So the optimal solution is obtained as follows:

ΔU(k)opt=12N1M\Delta U(k)_{opt}=\frac{1}{2}N^{-1}M (64)

V Simulation and Results

The Simulink/Carsim/Amesim co-simulation is developed under the vehicle speed of 30 km/h and 50 km/h, respectively. Based on the path planning of the tracking control module in the static environment, the target steering angle and vehicle speed are obtained, which will be utilized as the inputs for full drive-by-wire electric vehicles chassis control[6]. Following the output of the hierarchical chassis control, the ideal torque of four wheels and four angles will be produced, which are utilized as the inputs of Carsim. This paper will verify the path-tracking control strategies under various working situations.

V-A Results of planning and tracking control algorithm based on curvature calculation

A practicable path within a specific range is designed for the FDWEV, with various obstacles, the start point, and a target point to offer correct position information for the tracking control module. After obtaining the path point information, the generated points will be interpolated with a three-order spline. Then the points are processed using a five-order polynomial fitting for every 10 path points to make them meet the vehicle driving requirements and generate a reasonable path[40]. Then simulation settings with vehicle speeds of 30 km/h and 50 km/h are created in a specific scenario with considerable curvatures to validate the effectiveness of the tracking control algorithm.

(1) Vehicle speed is 30 km/h

According to the various deviations and curvature inputs, the output corresponding to the preview time TpT_{p} can be generated using the fuzzy controller, as illustrated in Fig. 6 (a). Based on the speed limitations for the curvature of the road, in this paper, we use the safety factor, which is defined as the adjustment factor λd\lambda_{d} = 0.65, and the adhesion coefficient μ=0.85\mu=0.85. As a result, the reference speed curve with the restriction can be obtained, and the speed tracking results show good performance by the chassis integrated control strategy, as shown in Fig. 6 (b).

Fig. 6 (c) depicts the path tracking results at a speed of 30 km/h working condition, and Fig. 6 (d) depicts the corresponding lateral deviation. To determine the present curvature, a delay is introduced with TDelay=0.065sT_{Delay}=0.065s, and the PID controller computes a curvature value. By repeated simulations, Ki=1.5K_{i}=1.5 is eventually determined, implying that the I controller is employed to regulate the deviation directly. A delay with TDelay=0.065sT_{Delay}=0.065s is also added to determine the preview deviation, the preview time determined by the fuzzy controller can then be multiplied by the reference speed to obtain the variable preview distance and the gain is set as GoutG_{out} = 0.8, which would produce a curvature value with LocalOffsetLimitLocalOffsetLimit = 0.2m. As a result, as illustrated in Fig. 6 (e), the steering wheel angle can be calculated, where the transmission ratio is chosen as 16. Further, as illustrated in Fig. 6 (f) with the lateral acceleration, it shows that the vehicle is mostly in the stable area and the steering curvature is significant, and near to 0.1, the lateral acceleration reaches its maximum, increasing the lateral force and allowing it to negotiate the curve successfully.

Refer to caption
(a)
Refer to caption
(b)
Refer to caption
(c)
Refer to caption
(d)
Refer to caption
(e)
Refer to caption
(f)
Figure 6: (a) TpT_{p} change curve; (b) Speed tracking results; (c) Path tracking results; (d) Lateral deviation results; (e) Corresponding steering wheel angle results; (f) Lateral acceleration results. The setting with CC-based method under 30 km/h.

(2) Vehicle speed is 50 km/h

Fig. 7 (a) depicts the obtained preview time TpT_{p} when the vehicle speed increases to 50 km/h, where the road curvature is large, the preview time and distance are both reduced, and the majority of the preview time is one second. Because the maximum adhesion given by the tires is regarded as the major speed restriction and the vehicle’s limit in speed planning, when the speed is raised, however, the vehicle speed cannot be instantly lowered if the curvature is larger than 0.1. Therefore, it is necessary to slow down the vehicle earlier by establishing a lower speed threshold. The vehicle’s speed planning and tracking results are illustrated in Fig. 7 (b). The tracking path and accompanying lateral deviation are determined by lowering the vehicle speed immediately before approaching the curve and allowing the vehicle to finish the steering operation for varied curvatures, as shown in Figs. 7 (c) and 7 (d). It creates a greater deviation than 30 km/h since increasing the speed makes the vehicle more prone to side slip during the steering, and even if the vehicle is in a stable zone in advance, by reducing the speed, the actuators will have a delay in taking action. As a result, although the curvature calculation (CC-based) method is straightforward to be calculated, it does not take into account different restrictions and real-time feedback correction according to the vehicle’s condition. Therefore, it will generate larger lateral deviations at higher vehicle speeds when the road curvature is rather considerable.

Refer to caption
(a)
Refer to caption
(b)
Refer to caption
(c)
Refer to caption
(d)
Refer to caption
(e)
Refer to caption
(f)
Figure 7: (a) TpT_{p} change curve; (b) Speed tracking results; (c) Path tracking results; (d) Lateral deviation results; (e) Corresponding steering wheel angle results; (f) Lateral acceleration results. The setting with CC-based method under 50 km/h.

Comparing the tracking results under different speeds, the CC-based tracking controller performs better when the vehicle speed is relatively lower in such a complicated environment. However, when the vehicle speed increases, it is not enough to reduce the speed to a relatively low level in advance where the curvature is significant. This is mostly because this method does not have real-time feedback correction of the vehicle’s state and considers different limits. As a result, it is not ideally suitable for an environment with greater operational difficulty. On the other hand, this approach is straightforward and does not require significant computation, so it is more applicable under typical working conditions.

V-B Results of tracking control algorithm based on MPC

The simulation settings of vehicle speed 30 km/h and 50 km/h have been specified separately to validate the effectiveness of the tracking controller based on the MPC, with the control goal and the process of continuous feedback optimization.

(1) Vehicle speed is 30 km/h

Based on the established vehicle model with both lateral and yaw directions in MPC, the road surface adhesion coefficient is μ=0.85\mu=0.85, and the MPC controller is written using the S-function in Simulink with parameters: sample period T=0.05sT=0.05s, prediction step Np=25N_{p}=25, control step Nc=10N_{c}=10, and the objective function weights are set as follows:

Q=[2000000010000000100000001000],R=1.5×105Q=\begin{bmatrix}&2000&0&0&0\\ &0&1000&0&0\\ &0&0&1000&0\\ &0&0&0&1000\end{bmatrix},R=1.5\times 10^{5} (65)

The slack factor is taken as 1000, the output deviation constraint is [-0.5, 0.5], and the front wheel steering angle constraint is [20-20^{\circ}, 2020^{\circ}]. Therefore, the results can be obtained and presented in Fig. 8. In Fig. 8 (a), the vehicle can maintain the longitudinal speed; the tracking control precision is within 0.3 m, which has a strong tracking capability in extremely complicated environments. From the lateral acceleration, the vehicle is in a rather stable area; only when the curvature is at its greatest extent will the lateral acceleration reach its greatest value. This is because there will be a greater requirement to increase the lateral force.

Refer to caption
(a)
Refer to caption
(b)
Refer to caption
(c)
Refer to caption
(d)
Refer to caption
(e)
Refer to caption
(f)
Figure 8: (a) TpT_{p} change curve; (b) Speed tracking results; (c) Path tracking results; (d) Lateral deviation results; (e) Corresponding steering wheel angle results; (f) Lateral acceleration results. The setting with MPC-based method under 30 km/h.

(2) Vehicle speed is 50 km/h

The simulation results are depicted in Fig. 9 following an increase in the vehicle speed. The vehicle is capable of maintaining the desired speed. The path control deviation in this complicated environment can be controlled to within about 0.5 m, and it can be seen from the lateral acceleration and yaw rate that an increase in vehicle speed does not result in a decrease in the performance of the vehicle’s stability. Similarly, except for the abrupt bends with the greatest curvature, the lateral acceleration will reach its maximum to give an adequate amount of lateral force, but the longitudinal speed will decrease. Because the combined effect is required to help the vehicle safely in a more complicated environment, in which decoupling the longitudinal and lateral motion is tough.

Refer to caption
(a)
Refer to caption
(b)
Refer to caption
(c)
Refer to caption
(d)
Refer to caption
(e)
Refer to caption
(f)
Figure 9: (a) TpT_{p} change curve; (b) Speed tracking results; (c) Path tracking results; (d) Lateral deviation results; (e) Corresponding steering wheel angle results; (f) Lateral acceleration results. The setting with MPC-based method under 50 km/h.

MPC tracking controller can produce satisfactory tracking results as well, when the speeds are relatively modest, there is no significant difference in the tracking precision provided by the two methods. However, in a complicated environment, when the vehicle speed rises, the curvature is still rather significant in some locations. MPC with the vehicle dynamics model can adjust the vehicle’s state and predict the vehicle’s output for a future period by continuous feedback optimization correction. Consequently, it also has an improved tracking capacity at faster speeds.

VI Conclusion

Based on the comprehensive control strategy of FDWEV chassis, different tracking controllers are designed to realize the trajectory tracking control of the vehicle in low and medium-speed working conditions with considerable curvatures to verify the presented algorithms. First, the repulsive force function and the direction are optimized to solve the unreachability of the target point in the standard APF approach. Then the corresponding speed planning is designed for the kinematic and dynamic constraints of the vehicle. Along with the kinematic and lateral dynamics models, two tracking controllers based on curvature calculation and MPC are designed in a complicated unstructured environment to improve tracking accuracy and stability. Furthermore, co-simulation in Simulink/Carsim/Amesim was conducted to validate the presented algorithms. Overall, based on the relatively significant curvature of the generated path, the two tracking controllers have strong tracking capabilities under low-speed working conditions with about 0.3 m deviation; when speed increases, the tracking capabilities can reduce, and the MPC-based controller with 0.5 m deviations can improve the following ability while maintaining better control compared to the CC-based controller with 0.6 m deviation. Hence, MPC can handle the optimization problem with constraints better in more dynamic unstructured environments.

Future studies will be focused on the real-world comparison of the two methods and the integration of collision avoidance control with dynamic environment information by radar and vision sensing systems.

References

  • [1] J. Guan, G. Chen, J. Huang, Z. Li, L. Xiong, J. Hou, and A. Knoll, “A discrete soft actor-critic decision-making strategy with sample filter for freeway autonomous driving,” IEEE Transactions on Vehicular Technology, 2022.
  • [2] W. Liu, L. Xiong, X. Xia, and Z. Yu, “Vehicle sideslip angle estimation: A review,” 2018.
  • [3] G. Chen, L. He, B. Zhang, and M. Hua, “Dynamics integrated control for four-wheel independent control electric vehicle,” International Journal of Heavy Vehicle Systems, no. 3-4, pp. 515–534, 2019.
  • [4] S. Cheng, L. Li, C.-Z. Liu, X. Wu, S.-N. Fang, and J.-W. Yong, “Robust lmi-based h-infinite controller integrating afs and dyc of autonomous vehicles with parametric uncertainties,” IEEE Transactions on Systems, Man, and Cybernetics: Systems, vol. 51, no. 11, pp. 6901–6910, 2020.
  • [5] R. Xu, H. Xiang, X. Xia, X. Han, J. Li, and J. Ma, “Opv2v: An open benchmark dataset and fusion pipeline for perception with vehicle-to-vehicle communication,” in 2022 International Conference on Robotics and Automation (ICRA).   IEEE, 2022, pp. 2583–2589.
  • [6] G. Chen, M. Hua, C. Zong, B. Zhang, and Y. Huang, “Comprehensive chassis control strategy of fwic-ev based on sliding mode control,” IET Intelligent Transport Systems, vol. 13, no. 4, pp. 703–713, 2019.
  • [7] W. Liu, X. Xia, L. Xiong, Y. Lu, L. Gao, and Z. Yu, “Automated vehicle sideslip angle estimation considering signal measurement characteristic,” IEEE Sensors Journal, vol. 21, no. 19, pp. 21 675–21 687, 2021.
  • [8] S. Zhao, G. Chen, M. Hua, and C. Zong, “An identification algorithm of driver steering characteristics based on backpropagation neural network,” Proceedings of the Institution of Mechanical Engineers, Part D: Journal of Automobile Engineering, vol. 233, no. 9, pp. 2333–2342, 2019.
  • [9] X. Xia, L. Xiong, W. Liu, and Z. Yu, “Automated vehicle attitude and lateral velocity estimation using a 6-d imu aided by vehicle dynamics,” in 2018 IEEE Intelligent Vehicles Symposium (IV).   IEEE, 2018, pp. 1563–1569.
  • [10] M. Hua, G. Chen, C. Zong, and L. He, “Research on synchronous control strategy of steer-by-wire system with dual steering actuator motors,” International Journal of Vehicle Autonomous Systems, vol. 15, no. 1, pp. 50–76, 2020.
  • [11] W. Liu, K. Quijano, and M. M. Crawford, “Yolov5-tassel: Detecting tassels in rgb uav imagery with improved yolov5 based on transfer learning,” IEEE Journal of Selected Topics in Applied Earth Observations and Remote Sensing, vol. 15, pp. 8085–8094, 2022.
  • [12] R. Xu, H. Xiang, Z. Tu, X. Xia, M.-H. Yang, and J. Ma, “V2x-vit: Vehicle-to-everything cooperative perception with vision transformer,” arXiv preprint arXiv:2203.10638, 2022.
  • [13] L. Xiong, X. Xia, Y. Lu, W. Liu, L. Gao, S. Song, Y. Han, and Z. Yu, “Imu-based automated vehicle slip angle and attitude estimation aided by vehicle dynamics,” Sensors, vol. 19, no. 8, p. 1930, 2019.
  • [14] R. Xu, Z. Tu, H. Xiang, W. Shao, B. Zhou, and J. Ma, “Cobevt: Cooperative bird’s eye view semantic segmentation with sparse transformers,” arXiv preprint arXiv:2207.02202, 2022.
  • [15] W. Liu, L. Xiong, X. Xia, Y. Lu, L. Gao, and S. Song, “Vision-aided intelligent vehicle sideslip angle estimation based on a dynamic model,” IET Intelligent Transport Systems, vol. 14, no. 10, pp. 1183–1189, 2020.
  • [16] R. Xu, Y. Guo, X. Han, X. Xia, H. Xiang, and J. Ma, “Opencda: an open cooperative driving automation framework integrated with co-simulation,” in 2021 IEEE International Intelligent Transportation Systems Conference (ITSC).   IEEE, 2021, pp. 1155–1162.
  • [17] M. Hua, Q. Zhou, C. Wang, C. Zhang, B. Shuai, and H. Xu, “Surrogate modelling for battery state-of-charge estimation in electric vehicles based on pseudo-2-dimensional model and gradient boosting machines,” 2021.
  • [18] F. Yan, J. Wang, C. Du, and M. Hua, “Multi-objective energy management strategy for hybrid electric vehicles based on td3 with non-parametric reward function,” Energies, vol. 16, no. 1, pp. 1–18, 2022.
  • [19] J. A. Oroko and G. Nyakoe, “Obstacle avoidance and path planning schemes for autonomous navigation of a mobile robot: a review,” in Proceedings of the Sustainable Research and Innovation Conference, 2022, pp. 314–318.
  • [20] L. Xiong, X. Xia, Y. Lu, W. Liu, L. Gao, S. Song, and Z. Yu, “Imu-based automated vehicle body sideslip angle and attitude estimation aided by gnss using parallel adaptive kalman filters,” IEEE Transactions on Vehicular Technology, vol. 69, no. 10, pp. 10 668–10 680, 2020.
  • [21] K. Bergman, O. Ljungqvist, and D. Axehill, “Improved optimization of motion primitives for motion planning in state lattices,” in 2019 IEEE Intelligent Vehicles Symposium (IV).   IEEE, 2019, pp. 2307–2314.
  • [22] T. Rybus, M. Wojtunik, and F. L. Basmadji, “Optimal collision-free path planning of a free-floating space robot using spline-based trajectories,” Acta Astronautica, vol. 190, pp. 395–408, 2022.
  • [23] S. Cheng, L. Li, H.-Q. Guo, Z.-G. Chen, and P. Song, “Longitudinal collision avoidance and lateral stability adaptive control system based on mpc of autonomous vehicles,” IEEE Transactions on Intelligent Transportation Systems, vol. 21, no. 6, pp. 2376–2385, 2019.
  • [24] H. Lu, Q. Zong, S. Lai, B. Tian, and L. Xie, “Real-time perception-limited motion planning using sampling-based mpc,” IEEE Transactions on Industrial Electronics, 2022.
  • [25] N. Wahid, H. Zamzuri, N. H. Amer, A. Dwijotomo, S. A. Saruchi, and S. A. Mazlan, “Vehicle collision avoidance motion planning strategy using artificial potential field with adaptive multi-speed scheduler,” IET Intelligent Transport Systems, vol. 14, no. 10, pp. 1200–1209, 2020.
  • [26] D.-m. Wu, Y. Li, C.-q. Du, H.-t. Ding, Y. Li, X.-b. Yang, and X.-y. Lu, “Fast velocity trajectory planning and control algorithm of intelligent 4wd electric vehicle for energy saving using time-based mpc,” IET Intelligent Transport Systems, vol. 13, no. 1, pp. 153–159, 2019.
  • [27] J. M. Snider et al., “Automatic steering methods for autonomous automobile path tracking,” Robotics Institute, Pittsburgh, PA, Tech. Rep. CMU-RITR-09-08, 2009.
  • [28] R. Xiong, L. Li, C. Zhang, K. Ma, X. Yi, and H. Zeng, “Path tracking of a four-wheel independently driven skid steer robotic vehicle through a cascaded ntsm-pid control method,” IEEE Transactions on Instrumentation and Measurement, vol. 71, pp. 1–11, 2022.
  • [29] I. Cervantes and J. Alvarez-Ramirez, “On the pid tracking control of robot manipulators,” Systems & control letters, vol. 42, no. 1, pp. 37–46, 2001.
  • [30] Z. Li, X. Ma, and Y. Li, “Robust tracking control strategy for a quadrotor using rpd-smc and rise,” Neurocomputing, vol. 331, pp. 312–322, 2019.
  • [31] T. Manzoor, X. Yuanqing, Z. Di-Hua, and M. Dailiang, “Trajectory tracking control of a vtol unmanned aerial vehicle using offset-free tracking mpc,” Chinese Journal of Aeronautics, vol. 33, no. 7, pp. 2024–2042, 2020.
  • [32] M. Hua, G. Chen, B. Zhang, and Y. Huang, “A hierarchical energy efficiency optimization control strategy for distributed drive electric vehicles,” Proceedings of the Institution of Mechanical Engineers, Part D: Journal of Automobile Engineering, vol. 233, no. 3, pp. 605–621, 2019.
  • [33] W. Liu, L. Xiong, X. Xia, and Z. Yu, “Intelligent vehicle sideslip angle estimation considering measurement signals delay,” in 2018 IEEE Intelligent Vehicles Symposium (IV).   IEEE, 2018, pp. 1584–1589.
  • [34] B. Patle, A. Pandey, D. Parhi, A. Jagadeesh et al., “A review: On path planning strategies for navigation of mobile robot,” Defence Technology, vol. 15, no. 4, pp. 582–606, 2019.
  • [35] H. M. Jayaweera and S. Hanoun, “A dynamic artificial potential field (d-apf) uav path planning technique for following ground moving targets,” IEEE Access, vol. 8, pp. 192 760–192 776, 2020.
  • [36] W. Liu, L. Xiong, B. Leng, H. Meng, and R. Zhang, “Vehicle stability criterion research based on phase plane method,” SAE Technical Paper, Tech. Rep., 2017.
  • [37] L. Gao, L. Xiong, X. Lin, X. Xia, W. Liu, Y. Lu, and Z. Yu, “Multi-sensor fusion road friction coefficient estimation during steering with lyapunov method,” Sensors, vol. 19, no. 18, p. 3816, 2019.
  • [38] R. Zhang, L. Xiong, Z. Yu, and W. Liu, “A nonlinear dynamic control design with conditional integrators applied to unmanned skid-steering vehicle,” SAE Technical Paper, Tech. Rep., 2017.
  • [39] G. Chen, J. Hou, J. Dong, Z. Li, S. Gu, B. Zhang, J. Yu, and A. Knoll, “Multiobjective scheduling strategy with genetic algorithm and time-enhanced a* planning for autonomous parking robotics in high-density unmanned parking lots,” IEEE/ASME Transactions on Mechatronics, vol. 26, no. 3, pp. 1547–1557, 2020.
  • [40] M. Elhoseny, A. Tharwat, and A. E. Hassanien, “Bezier curve based path planning in a dynamic field using modified genetic algorithm,” Journal of Computational Science, vol. 25, pp. 339–350, 2018.