It is a striking fact that the path tracking accuracy of autonomous vehicles based on active front wheel steering is poor under high-speed and large-curvature conditions. In this study, an adaptive path tracking control strategy that coordinates active front wheel steering and direct yaw moment is proposed based on model predictive control algorithm. The recursive least square method with a forgetting factor is used to identify the rear tire cornering stiffness and update the path tracking system prediction model. To adaptively adjust the priorities of path tracking accuracy and vehicle stability, an adaptive strategy based on fuzzy rules is applied to change the weight coefficients in the cost function. An adaptive control strategy for coordinating active front steering and direct yaw moment is proposed to improve the path tracking accuracy under high-speed and large-curvature conditions. To ensure vehicle stability, the sideslip angle, yaw rate and zero moment methods are used to construct optimization constraints based on the model predictive control frame. It is verified through simulation experiments that the proposed adaptive coordinated control strategy can improve the path tracking accuracy and ensure vehicle stability under high-speed and large-curvature conditions.
1 Introduction
The rapid development of artificial intelligence technology, it has brought new opportunities and challenges to autonomous vehicles, which have received increasing attention [1‐4]. The main tasks in autonomous vehicle systems include environmental perception, vehicle positioning, behavior decision-making, motion planning, and execution control. As the core task in execution control, path tracking should ensure that the vehicle accurately follows the reference path and remains vehicle stability [5‐8].
In active front wheel steering (AFS), steering operations can be applied to correct understeer or oversteer. AFS has been extensively studied and applied for path tracking, and shown to have little effect on vehicle longitudinal dynamics and ride comfort. In Ref. [9], a switched strategy was proposed and the effects of different error models on the vehicle transient and steady-state characteristics were analyzed. Lyapunov stability arguments were used to exploit the D-stability of vehicle path tracking closed-loop system to improve its transient behaviors [10]. Inspired by a model-free controller, an ultra-local model predictive control strategy for path tracking was proposed in Ref. [11]. To handle time-varying parameters, a robust lateral control strategy based on H∞ control was studied [12]. A dynamic path tracking controller for a double-steering mobile robot on slippery grounds was designed in Ref. [13].
Advertisement
Vehicle limiting control methods to meet vehicle safety requirements under high-speed and large-curvature conditions have received increasing attention. Many control algorithms have been employed to improve the controller performance of AFS vehicles under extreme conditions. The center of percussion in the vehicle was used to design steering controller for autonomous racing vehicles in Ref. [14]. The vehicle sideslip angle in the feedback-feedforward control law was introduced in Ref. [15] to improve the path tracking accuracy and stability at the limits of handling. An obstacle avoidance and vehicle stability control strategy using safe envelopes based on model predictive control (MPC) was proposed in Refs. [16, 17]. The control strategy for drifting along the reference path beyond vehicle stability limits was studied in Ref. [18]. However, the controller performance is limited when the tire lateral force approaches the limits of handling.
Direct yaw moment control (DYC) can correct the vehicle posture by using differential braking to generate yaw moment. Coordinated control strategies based on AFS and DYC are therefore widely used for vehicle path tracking. Integrated longitudinal and lateral vehicle stability control was realized using a modular optimal control structure-based MPC, and the tracking errors were minimized using longitudinal control and yaw moment [19]. To enhance vehicle directional stability and steerability, a new integrated control system based on nonlinear MPC was designed to coordinates active torque vectoring and electronic stability control [20]. A robust MPC with finite time horizon for path tracking was studied to address parametric uncertainties and external disturbances [21]. In Ref. [22], path tracking control via second-order sliding mode and nonlinear disturbance observer was studied. The coordinated strategy between path tracking and DYC based on vehicle sideslip angle estimation was proposed in Ref. [23]. In Ref. [24], MPC was combined with sliding surface control to track the reference yaw rate based on coordinated control frame. In the above works, the control strategies was coordinated by DYC throughout the entire process of path tracking, and the advantages of AFS were not fully utilized. Differential braking affected the vehicle longitudinal dynamics and reduced the vehicle speed.
The tire cornering stiffness is an important parameter that reflects the tire dynamics. The tire dynamics tends to be in the nonlinear or saturated regime under high-speed and large-curvature conditions. A robust H∞ output-feedback control method for path tracking was proposed to deal with tire cornering stiffness uncertainty [25]. In Ref. [26], a novel robust adaptive indirect control method based on an exponential-like sliding-mode fuzzy type-2 neural network approach was proposed to enhance the path tracking performance. A robust event-triggered automatic steering control approach with H∞ performance was studied in Ref. [27]. This methods use the bounded disturbance energy hypothesis to handle parameter uncertainties. The choice of the assumed bounded range is important because an inappropriate choice may lead to excessive conservativeness. A parameter identification model for tire cornering stiffness was derived in Ref. [28] based on vehicle dynamics model, and the tire cornering stiffness in the linear segment was measured in low-speed circle test. The sideslip angle was eliminated, and the normalized tire lateral stiffness estimated using the recursive least square method [29]. As the amount of online observation data increased, the identification algorithm became susceptible to dimensional disasters and excessive reference to historical data.
Based on the above previous works, a novel adaptive coordinated path tracking control strategy with direct yaw moment control based on MPC is proposed in this study to improve the tracking accuracy and ensure vehicle stability. The architecture of the adaptive coordinated MPC path tracking control scheme is shown in Figure 1. The main innovations and contributions of this study are as follows: (1) The tire nonlinear dynamic characteristics are described using a linear tire model. An online tire stiffness identification method is proposed in which the least square method with a forgetting factor is used to update the system prediction model parameters to improve the accuracy of vehicle state prediction. (2) To improve the tracking accuracy under high-speed and large-curvature conditions, an adaptive coordinated path tracking control strategy was proposed, the weight coefficient of the objective cost function is changed using fuzzy rules, and adaptive coordination between path tracking and DYC is realized. (3) The adaptive coordinated MPC controller is designed and tested on the CarSim-Simulink platform under these conditions.
×
Advertisement
The organization of this paper is as follows: The model of the path tracking control system and controller design are presented in Section 2. The adaptive coordinated control strategy is presented in Section 3. The simulation is presented in Section 4. Section 5 concludes the paper with a brief discussion of the results.
2 Model of Path Tracking Controller for Autonomous Steering
2.1 Vehicle Dynamics Model
Because the proposed controller requires the vehicle dynamics information under high-speed and large-curvature conditions, the vehicle lateral, yaw, and roll dynamics are established as shown in Figure 2 to capture the essential vehicle dynamics state parameters. The tires are the only components that connect the road to the vehicle. All movements, including the starting, acceleration, braking, and turning of the vehicle, are realized through the tires. During the path tracking process under high-speed and large-curvature conditions, vehicle yaw moment is provided by the lateral force of the front and rear tires. The lateral acceleration of the vehicle is mainly caused by the lateral force of the front and rear tires. At the same time, the coupling relationship between the yaw rate and longitudinal velocity can produce additional vehicle lateral acceleration. The vehicle roll dynamics are described using the characteristics of the suspension damping and stiffness considering the coupling relationship between the vehicle lateral velocity, longitudinal velocity, and roll dynamics.
×
In Figure 2, m is the vehicle total mass. h is the height of the sprung mass from the roll center, lf and lr are the distances from the center of gravity to the front and rear axles, respectively. ls is the half distance between the left and right tires. g is the acceleration due to gravity. vx and vy are the longitudinal and lateral speed, respectively. r and ϕ are the yaw rate and roll angle, respectively. Fx1 and Fx3 are the longitudinal tire force of the front and rear axles. Fy1 and Fy3 are the lateral tire force of the front and rear axles. δ and β are the front tire steering angle and vehicle sideslip angle. θ is the vehicle yaw angle. K and D are the suspension roll damping and stiffness.
where ms is the vehicle sprung mass. M is the external yaw moment. Iz is the moment of inertia about z-axis. Ix is the moment of inertia of sprung mass about the x-axis. X and Y are the coordinate positions of the vehicle in XOY coordinate system.
Under the small-angle approximation, the vehicle dynamics model can be approximated as
The Fiala brush tire model is highly accurate and fully accounts for the nonlinear dynamic characteristics. The lateral force of the tire can be described as a function of the tire slip angle.
where α and Cα are the tire slip angle and cornering stiffness, respectively. μ is the adhesion coefficient between the road surface and the tire. Fz is the vertical force.
Because the tire slip angle does not directly participate in the control optimization solution process and the vehicle lateral speed is relatively small compared to the longitudinal speed, the tire slip angle of the front and rear tires can be approximated as
To make full use of the tire nonlinear dynamics and reduce the nonlinear complexity of the controller, the front tire lateral force can be considered as the control input for the MPC optimization and mapped to the desired δ via
The nonlinear dynamics of the rear tire should be properly accounted for to approximate the MPC linear optimization problem accurately. The steady-state solution of the rear lateral force is expressed as
It is desired that the path tracking should follow the reference path accurately by minimizing the lateral and heading deviations while maintaining rollover and lateral stability. The relationship between the vehicle and reference path is illustrated in Figure 3, where the CM point represents the center of vehicle mass.
×
The path tracking kinematic relationship can be expressed as
where θ and θd are the actual yaw angle and reference yaw angle of vehicle, respectively. κ(s) is the curvature of the reference path at the position s.
2.4 Design of Path Tracking Controller Based on MPC
2.4.1 Prediction Model
The controller state space model, in which the front tire lateral force and external yaw moment are taken as the control inputs, can be derived from Eqs. (2), (4), (8), and (9) as
To facilitate controller design and implementation, the continuous-time state-space model is converted into a discrete increment system using previous Euler method and expressed as Eq. (11).
The path tracking control objective of the MPC controller is the solution of a convex optimization problem at each sampling step. The first optimal value of the control sequence is used as the future input. The objective function and constraints can be expressed as
where ε is a non-negative slack variable used to ensure that the optimization problem is always feasible. The optimal front lateral force input Fyf and the external yaw moment M can be obtained using a look-up table and yaw moment allocation algorithm. To accurately capture the propagation of β, r and ϕ at high frequency, the sampling time T is set to 0.02 s considering the accuracy of the captured vehicle information. Note that the values of the control horizon Nc and prediction horizon Np are set to Nc = 20 and Np = 30 based on control accuracy and calculation efficiency considerations. The weighting matrices are obtained by iteratively tuning, R = diag{10, 1}, Q = diag{1000, 5}, and W = 10.
2.4.3 Stability Constraints
The vehicle lateral stability constraints are defined by the bounds of the two key variables of vehicle sideslip angle β and yaw rate r. The bounds of the β and r reflect the maximum capabilities of the tire under the assumptions of steady-state cornering [30]. The maximum steady-state yaw rate and vehicle sideslip angle can be expressed as
Vehicle rollover stability is a significant concern in transportation design. In particular, vehicle rollover stability is especially important under high-speed and large-curvature extreme conditions. To predict the vehicle rollover propensity, the zero-moment point (ZMP) metric is applied to the projected vehicle trajectories. The ZMP is given by Ref. [31].
The vehicle rollover stability constraints defined by Eq. (23) can be expressed as Eq. (24).
$$- l_{s} \le y_{ZMP} \le l_{s} .$$
(24)
3 Adaptive Coordinated Control for Path Tracking
When the vehicle is under the extreme conditions of high speed and large-curvature path, the tire slip angle is strictly restricted in the method proposed in Refs. [7, 9] to ensure vehicle stability. This results in a steady state steering phenomenon with poor path tracking control performance in which the steering states remain stable. Therefore, an adaptive coordinated control strategy is proposed here in which the tire cornering stiffness is identified online, the weight coefficient of the objective cost function is adaptively changed, and the yaw moment control is adaptively coordinated to improve the vehicle path tracking performance and ensure vehicle stability under extreme conditions.
3.1 Tire Cornering Stiffness Identification Based on Recursive Least Square
To reduce the computational burden of the path tracking controller based on model predictive control, a continuous linearized tire model is used to establish the predictive model. To account for the nonlinear tire dynamic characteristics, a control strategy is proposed based on the optimal front tire lateral force. However, because errors for the lateral force of the rear tire from the model linearization are still present under high-speed and large-curvature conditions, the recursive least square method with a forgetting factor is used to determine the rear tire cornering stiffness.
3.1.1 Recursive Model
A simplified two-degrees of freedom (DOF) vehicle dynamics model is established to determine the tire cornering stiffness, as illustrated in Figure 4.
×
Under the small-angle assumption approximation, the vehicle dynamics model can be expressed as
Considering the vehicle data for the first k steps and transforming the above equation into the least squares form, the recursive model of the vehicle tire cornering stiffness can be expressed as
3.1.2 Recursive Least Square Method with Forgetting Factor
The recursive least square method is modified to provide new parameter identification based on the previous steps. However, the parameter identification of the tire cornering stiffness may become inaccurate because of the data saturation phenomenon. Therefore, a forgetting factor is introduced to overcome the problem of data saturation by reducing the impact of old data. The recursive model can be rewritten as
The tire cornering stiffness at the next moment is identified by updating the prediction model of the vehicle path tracking system with the current parameter identification
3.2 Adaptive Strategy of Weight Coefficients Based on Fuzzy Rule
To ensure high tracking accuracy and improve vehicle stability, an adaptive strategy for the weight coefficients is applied based on fuzzy rules. Based on the components of the objective cost function, the lateral deviation, heading deviation ratio, and vehicle sideslip angle ratios are chosen as the fuzzy control inputs, which can be expressed as
The weight coefficients of each index in the objective cost function are then adaptively changed, and the priorities for tracking performance and vehicle stability adjusted. The inputs of the fuzzy controller can be fuzzified into the five fuzzy sets of ZO (zero), PSr (positive smaller), PS (positive small), PB (positive big), and PBr (positive larger). The lateral and heading deviations, and the vehicle stability performance weight ratios (sideslip angle, yaw rate, and roll angle) are similarly chosen as the fuzzy control outputs and fuzzified into the four fuzzy sets of ZO (zero), PS (positive small), PM (positive medium), and PB (positive big).
The correlations between the inputs and outputs in the fuzzy rules are constructed based on driving experience and the consideration of both tracking accuracy and ride comfort when tracking the predetermined path, and listed in Tables 1, 2, 3.
Table 1
Lateral deviation fuzzy rules for weight ratio
Qe
Ie
ZO
PSr
PS
PB
PBr
Iθ
ZO
ZO
PS
PS
PM
PB
PSr
ZO
PS
PS
PM
PB
PS
ZO
PS
PS
PM
PB
PB
ZO
PS
PS
PM
PB
PBr
ZO
PS
PS
PM
PB
Table 2
Heading deviation fuzzy rules for weight ratio
Qθ
Ie
ZO
PSr
PS
PB
PBr
Iθ
ZO
ZO
PS
PS
PM
PB
PSr
ZO
PS
PS
PM
PB
PS
ZO
PS
PS
PM
PB
PB
ZO
PS
PS
PM
PB
PBr
ZO
PS
PS
PM
PB
Table 3
Vehicle stability fuzzy rules for weight ratio
Qβ
Ie
ZO
PSr
PS
PB
PBr
Iβ
ZO
ZO
PS
PS
PM
PB
PSr
ZO
PS
PS
PM
PB
PS
ZO
PS
PS
PM
PB
PB
ZO
PS
PS
PM
PB
PBr
ZO
PS
PS
PM
PB
3.3 Coordinated Strategy for Direct Yaw Moment
Active front wheel steering is an effective means of ensuring the lateral stability of the vehicle. However, it may lead to understeering under high-speed and large-curvature conditions. DYC can give full play to the vehicle yaw dynamics and has a significant effect on restraining vehicle understeer. Therefore, an adaptive control strategy for coordinating active steering with direct yaw moment under high-speed and large-curvature conditions is proposed to improve tracking performance, as shown in Figure 5.
×
3.3.1 Analysis of Vehicle Steady State Steering
As shown in Figure 6, when the autonomous vehicle completes steady-state steering with the maximum steering ability, the lateral force of the front tires and lateral acceleration should satisfy Eq. (34).
The vehicle motion under steady-state steering motion is approximated as uniform circular motion in the sampling period. The required centripetal acceleration can then be expressed as
Based on the above analysis, the lateral acceleration and lateral force of the tires are chosen as performance indicators for triggering the switching rule.
3.3.2 Adaptive Switching Rules
When the switching rules are not triggered, active front wheel steering control is chosen for path tracking. The switching rules are as follows:
1.
At time k, calculate vehicle reference lateral acceleration.
if (|Fy| ≥ |\(F_{yf}^{ss}\) − τ| and |ay| ≥ |\(a_{y}^{ss}\)|
QM = 1;
Update control matrix and objective cost function;
Optimization: Find the optimal U(k) = [FyM]T (U(k) = Fy).
3.
Set k = k + 1, and update system states and state space model.
In the above, QM is the weight coefficient of the external yaw moment, τ is the buffer factor, which is set to the value of 5.
When the vehicle exits the coordinated control of active front wheel steering and direct yaw moment, the external yaw moment is not directly returned to zero to avoid a sudden change caused by updating the control quantity weight and control matrix. The external yaw moment instead satisfies the following relationship.
$$M(k) = M_{\max } - \Delta MTk,$$
(37)
where ∆M is maximum change of yaw moment, and T is the sampling time.
When the vehicle is on a small-curvature path, the AFS controller working mode is adopted, and the controller outputs the desired front tire lateral force. When the vehicle is on a large-curvature path, the coordinated yaw moment control starts to work, and the AFS + DYC controller is adopted. The controller outputs the desired front tire lateral force and external yaw moment. This controller is superior because it can reduce the vehicle yaw rate (shown in Eq. (1)) and thereby reduce the heading and lateral position deviations (shown in Eq. (9)).
3.4 External Yaw Moment Distribution
The external yaw moment M generated by the MPC controller should be allocated to the four tires. The lateral force of the front tires is saturated. Therefore, differential braking of the rear tires is used to generate the desired external yaw moment. This can be translated into a multi-objective optimization problem in which a quadratic function is applied to establish the objective cost function for achieving the desired yaw moment with the minimum tire force. The objective function and constraints can be expressed as
where Q1 = diag{1, 1} is a weighting positive-definite diagonal matrix and c = [2 2]T is an offset vector.
4 Simulation
4.1 Reference Path and Vehicle Parameters
The proposed adaptive coordinated MPC controller was verified using MATLAB/Simulink and CarSim. In this section, two simulation cases are presented to verify the effectiveness of the proposed MPC path tracking controller. The vehicle parameters are presented in Table 4. The reference path was parameterized as the curvature profile shown in Figure 7 and the position profile shown in Figure 8 using the path generation method proposed in Refs. [32, 33].
Table 4
The main vehicle parameters
Parameter
Value
Vehicle mass m (kg)
1610
Vehicle sprung mass ms (kg)
1430
Yaw inertia Iz (kg·m2)
2059.2
Roll inertia Ix (kg·m2)
700.7
Distance from front axle to gravity center lf (m)
1.05
Distance from rear axle to gravity center lr (m)
1.61
Distance between left and right tires 2ls (m)
1.565
Height of the sprung mass from the roll center h (m)
0.65
Front cornering stiffness Cf (N/rad)
67862
Rear cornering stiffness Cr (N/rad)
45714
Suspension roll damping K (N·m/rad)
145330
Suspension roll stiffness D (N·m·s/rad)
4500
Friction coefficient μ
0.85
×
×
4.2 Case 1
To verify the performance of the adaptive coordinated controller, the road adhesion coefficient of 0.85 and a constant vehicle speed of 69 km/h were set in the simulation. The first MPC controller (AFS MPC) control input is the lateral force of the front tires, for which the simulation results are represented by black dotted lines in the following figures, and those of the adaptive coordinated controller (AFS + DYC MPC) by blue solid lines.
As can be seen from Figure 9, the controllers performed well under high-speed and large-curvature conditions. The path generated by the proposed controller is closer to the reference path (represented by the red solid line). Although the tracking performance decreased at larger curvatures, the proposed controller still achieved better control performance.
×
As can be seen from Figures 10 and 11 and Tables 5 and 6, the absolute value of the maximum value of the lateral deviation (Max abs(e)) is reduced by 13.0%, and that of the average value (AV abs(e)) reduced by 43.5% for the proposed controller compared to the AFS controller, and the former has a smaller absolute value of the mean square error (MSE abs(e)). For the heading deviation, although AV abs(θe) is decreased by 20.0%, Max abs(θe) is increased by 4.2%.
Table 5
Lateral deviation comparison
Controllers
AV abs(e) (m)
MSE abs(e) (m)
Max abs(e) (m)
AFS
0.23
0.04
0.54
AFS + DYC
0.13
0.03
0.47
Table 6
Heading deviation comparison
Controllers
AV abs(θe) (°)
MSE abs(θe) (°)
Max abs(θe) (°)
AFS
0.80
0.008
2.60
AFS + DYC
0.64
0.01
2.74
×
×
Compared with the AFS controller, the peak heading angle of the proposed controller appeared later. To avoid sudden changes, the yaw moment changed linearly when the proposed controller exited, which caused the peak of the heading angle deviation to be delayed with a relatively larger Max abs(θe) value of 2.74°. Therefore, the proposed controller is more effective for path tracking under high-speed and large-curvature conditions.
As shown in Figures 12, 13, 14, both controllers could ensure vehicle stability during path tracking. The maximum vehicle sideslip angle did not exceed 3°, the yaw rate did not exceed 5 rad/s, and the maximum vehicle roll angle did not exceed 3°. The proposed controller provides better vehicle stability, especially in terms of the peak values of the vehicle sideslip angle, roll angle and the yaw rate.
×
×
×
Figures 15 and 16 show the relationships between the external yaw moment (M), tire lateral force (Fy), steady state vehicle lateral acceleration multiplied by 1000 (1000 × \(a_{y}^{ss}\)), actual vehicle lateral acceleration multiplied by 1000 (1000 × ay), and path (Station). The proposed adaptive coordinated control strategy of active front wheel steering and direct yaw moment was initiated at positions 1 and 2 when the tire lateral force and vehicle acceleration satisfied the switching rules. The external yaw moment changed linearly at position 3 at the exit of the adaptive control strategy.
×
×
As shown in Figure 17, the observed value of the tire cornering stiffness was zero at the initial moment. This is because the data samples for the recursive matrices M and N at the initial moment were small and the random error was large, which resulted in large fluctuations in the observation results. The observation output value was therefore defined as 0. When the sample data reached 100 groups, the matrices M and N were updated. Near the curvature peak of the reference path, the tire dynamics exhibited strong nonlinear characteristics, and the tire cornering stiffness reached its minimum peak value and remained stable. As the curvature gradually decreased, the observed value gradually converged to the equivalent cornering stiffness (constant value) of the linear tire model.
×
4.3 Case 2
To further verify the performance of the adaptive coordinated controller under extreme conditions, the vehicle speed was set to 57 km/h and the nominal road adhesion coefficient to 0.85. The actual road adhesion coefficient is shown in Figure 18. The reference path and its curvature are shown in Figures 7 and 8, respectively. The MPC controller (AFS MPC) control input was the lateral force of the front tires. The simulation results for AFS MPC are represented by black dotted lines, and those for the adaptive coordinated controller (AFS + DYC MPC) by blue solid lines in Figures 18, 19, 20.
×
×
×
As can be seen from Figures 19 and 20, the absolute values of the maximum lateral deviations are 0.25 and 0.22 for the AFS and the proposed controller, respectively. The absolute value of the maximum value was reduced in the latter by 12.0%. The proposed controller exhibited better tracking performance. In particular, the superiority of the proposed controller in the areas of the road with low adhesion and large curvature are more significant when there are uncertainties in the road adhesion coefficient. The peak heading angle of the heading deviation appeared later for the proposed controller compared to the AFS controller. This is because the yaw moment changed linearly at the exit of the proposed controller to avoid sudden changes, which caused the peak of the heading angle deviation to be delayed and have a relatively large value. Therefore, the proposed controller is more effective for path tracking under high-speed and large-curvature conditions with uncertain values of the road adhesion coefficient.
As shown in Figures 21 and 22, both controllers could ensure vehicle stability during path tracking. The maximum vehicle sideslip angle did not exceed 0.70°, and the yaw rate did not exceed 0.35°/s. However, the local stability performance of the AFS controller was slightly better than that of the proposed controller, as shown in Figures 21 and 22. This is because when the vehicle was on the peak curvature portion of the road, the vehicle gradually entered into the turning steady state (the vehicle sideslip angle and yaw rate tended to stabilize) during the process of path tracking. At this time, DYC began to come into effect, which resulted in changes to the vehicle input and fluctuations in the vehicle stability indicators. To overcome these fluctuations, constraints were added to the change in yaw moment constraints at the moment of yaw moment intervention and withdrawal in this study. During the design process of the AFS and proposed controllers, the anti-instability constraints were constructed using the vehicle sideslip angle and yaw rate to ensure vehicle lateral stability. Therefore, vehicle stability under both strategies can be guaranteed, as can be verified from the results shown in Figures 21 and 22.
×
×
5 Conclusions
(1)
In this study, the state-space model of the path tracking control system was established based on the vehicle dynamics, tire dynamics, and path tracking error models which are used to predict the system states in the prediction horizon.
(2)
To improve the tracking accuracy and ensure vehicle stability under high-speed and large-curvature conditions, an adaptive coordinated path tracking control strategy was proposed. Under the strategy, the system prediction model is updated through tire parameter identification, the weight coefficient of the objective cost function is changed using fuzzy rules, and adaptive coordination between path tracking and DYC is realized.
(3)
A path tracking controller was designed based on linear time-varying model predictive control algorithm that can systematically deal with vehicle stability constraints and control variable constraints.
(4)
The results of the joint CarSim and Simulink simulation test showed that the adaptive coordinated control strategy is feasible. The control strategy can not only improve the path tracking accuracy but also ensure vehicle stability. Nevertheless, because parameter uncertainties, model errors, and external disturbances were not considered, a robust coordinated control strategy and hardware-in-the-loop test will be further studied in the future.
Acknowledgements
Not applicable.
Competing Interests
The authors declare no competing financial interests.
Open AccessThis article is licensed under a Creative Commons Attribution 4.0 International License, which permits use, sharing, adaptation, distribution and reproduction in any medium or format, as long as you give appropriate credit to the original author(s) and the source, provide a link to the Creative Commons licence, and indicate if changes were made. The images or other third party material in this article are included in the article's Creative Commons licence, unless indicated otherwise in a credit line to the material. If material is not included in the article's Creative Commons licence and your intended use is not permitted by statutory regulation or exceeds the permitted use, you will need to obtain permission directly from the copyright holder. To view a copy of this licence, visit http://creativecommons.org/licenses/by/4.0/.