Next Article in Journal
Robotic Sponge and Watercolor Painting Based on Image-Processing and Contour-Filling Algorithms
Next Article in Special Issue
Research on an Intelligent Driving Algorithm Based on the Double Super-Resolution Network
Previous Article in Journal / Special Issue
Research on the Identification of Tyre-Road Peak Friction Coefficient under Full Slip Rate Range Based on Normalized Tyre Model
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Communication

Optimal Control Method of Path Tracking for Four-Wheel Steering Vehicles

1
School of Intelligent Systems Engineering, Sun Yat-sen University, Guangzhou 510006, China
2
Southern Marine Science and Engineering Guangdong Laboratory (Zhuhai), Zhuhai 519082, China
*
Author to whom correspondence should be addressed.
Actuators 2022, 11(2), 61; https://doi.org/10.3390/act11020061
Submission received: 18 January 2022 / Revised: 14 February 2022 / Accepted: 16 February 2022 / Published: 18 February 2022
(This article belongs to the Special Issue Actuators for Intelligent Electric Vehicles)

Abstract

:
Path tracking is a key technique for intelligent electric vehicles, while four-wheel steering (4WS) technology is of great significance to improve its accuracy and flexibility. However, the control methods commonly used in path tracking for a 4WS vehicle cannot take full advantage of the additional steering freedom of the 4WS vehicle, because of restricting the relationship between the front and rear wheels steering angle. To address this issue, we derive a kinematic model without the restriction based on the small-angle assumption. Then, the objective function and constraints of system control quantity optimization are designed based on the tracking error model. After the optimization problem is solved in the form of quadratic programming with constraints, the control sequence with the smallest performance index is obtained through rolling optimization. The proposed method is tested on a high-fidelity Carsim/Simulink co-simulation platform and an experimental vehicle. The results show that the standard deviation of the lateral error and the yaw angle error of the algorithm is less than 0.1 m and 3.0°, respectively. Compared with the other two algorithms, the control of the front and rear wheels angle of this method is more flexible and the tracking accuracy is higher.

1. Introduction

In recent years, unmanned vehicles have become a research hotspot due to the increase of various traffic problems such as traffic congestion and traffic accidents [1]. The key technologies mainly include environmental perception, precise localization, planning and decision-making, and motion control. Path tracking is one of the key problems of motion control for autonomous vehicles, which is denoted as tracking a predetermined path by controlling the lateral and yaw movement of the vehicle [2]. Thus, it can be defined as minimizing the lateral offset and heading errors [3].
Path tracking control methods can be mainly divided into two categories. One is geometry-based, which mainly includes pure pursuit (PP) [4] and Stanley [5], etc. The other is model-based, represented by synovial membrane control [6], linear quadratic regulator (LQR) [7,8] and model predictive control (MPC) [9,10], etc. Geometry-based control methods are often used in low-speed scenarios, with good interpretability and fast calculation speed. Model-based methods mainly based on dynamic models are often used for stability control of high-speed vehicles [11], whose disadvantages include poor real-time performance and the difficulty to obtain kinetic parameters accurately [12]. However, the above studies are mostly based on front-wheel steering (FWS) vehicles. The only control input for lateral tracking control is the front-wheel steering angle, which limits the ability of path tracking control.
To improve the flexibility and stability of vehicles, the concept of the 4WS vehicle was proposed in the late 1980s [13]. At low speed, the steering modes of a 4WS vehicle are more diverse than FWS vehicles [14,15]. The front and rear wheels can be turned in reverse phase to reduce the turning radius and improve maneuverability. At high speed, a 4WS vehicle can improve handling stability by steering the front and rear wheels in phase to ensure zero slip angle and ideal yaw rate [16]. Making full use of the additional degrees of freedom of the 4WS vehicle can independently control the path and attitude of the vehicle, reduce the yaw motion required by the body, and improve the responsiveness of the vehicle heading change [2]. At the same time, the vehicle has better path tracking performance due to the improvement of flexibility [17].
Aiming at the path tracking problem of the 4WS vehicle, Ye et al. [18] designed a strategy to switch steering modes include active front and rear steering (AFRS), Ackermann steering, and crab steering for achieving accurate path-following of the vehicle. Hiraoka et al. [6] proposed a 4WS vehicle path tracking controller based on the sliding mode control theory, which uses front and rear control points for tracking. However, the above methods restrict the steering freedom of the 4WS vehicle and reduce flexibility. Wu et al. [19] developed a novel rear-steering-based decentralized control (RDC) algorithm for the 4WS vehicle. Yin et al. [20] carried out a new distribution controller to allocate driving torques to four-wheel motors, which can use each tire to generate yaw moment and achieve a quicker yaw response. Fnadi et al. [21] synthesized a new controller for dynamic path tracking by using constrained model predictive control (MPC) for double steering off-road vehicles, which takes into account steering and sliding constraints to ensure safety and lateral stability. However, these methods only use rear-wheel steering within a small turning angle range and are not suitable for flexible control of 4WS vehicle at low speed.
Aiming at these challenges, a tracking error model unrestrained on the front and rear wheels steering (UFRWS) relationship of the 4WS vehicle is established in this paper. As shown in Figure 1, a predictive controller based on this model is proposed, which performs lateral motion control, and forms a trajectory tracking controller with the PI controller that performs longitudinal control. The advantage of this controller is that it can fully utilize the steering freedom of the 4WS vehicle, improving tracking accuracy and flexibility.

2. Kinematics Model of 4WS Vehicle

The kinematic model is the basis of trajectory planning and tracking control. To reduce the complexity of the controller design, the 4WS vehicle kinematics model can be simplified to a single-track model with the assumption of pure rolling and small steering angle as shown in Figure 2. The points F ( x f , y f ) and B ( x r , y r ) are the center of the front and the rear axle of the vehicle, respectively. The point M ( x , y ) is the geometric center of the vehicle, and the point C is the center of rotation of the vehicle. R denotes the radius of rotation of the vehicle. The wheelbase L is the distance between the front and rear axles, and the wheel track W refers to the distance between the left and right wheels. The heading angle φ refers to the angle between the body direction and the X axis in the global coordinate system X O Y . The center of mass slip angle β is the angle between the speed v m at the point M and the direction of the body.
The 4WS vehicle bicycle model is gray as shown in Figure 2. Its front steering angle δ f and rear steering angle δ r should satisfy the Ackerman steering geometric relationship. So, the steering angle of each wheel δ i ( i = f r , f l , r r , r l ) satisfies the Equation (1).
tan δ f l = tan δ f 1 W 2 L ( tan δ f tan δ r ) tan δ f r = tan δ f 1 + W 2 L ( tan δ f tan δ r ) tan δ r l = tan δ r 1 W 2 L ( tan δ f tan δ r ) tan δ r r = tan δ r 1 + W 2 L ( tan δ f tan δ r )
We take M as the control point. Then, the nonlinear kinematics equations of the 4WS vehicle bicycle model in the global coordinate system can be expressed as
X ˙ = v m cos ( φ + β ) Y ˙ = v m sin ( φ + β ) φ ˙ = v m cos ( β ) L tan δ f tan δ r β = arctan tan δ r + tan δ f 2
Most of the existing path tracking lateral control methods are designed for the application of front-wheel steering vehicles. Therefore, to apply PP and MPC methods to four-wheel steered vehicles, this article regards 4WS as FWS vehicles with the wheelbase halved by restricting the steering angles of the front and the rear to be equal and out of phase as shown in Figure 3. Then, Equation (2) can be simplified to Equation (3), which is the symmetrical front and the rear wheels steering (SFRWS) model of the 4WS vehicle. The PP and MPC methods based on the SFRWS model can be used as the comparison algorithm in this article for the method based UFRWS model.
X ˙ = v m cos φ Y ˙ = v m sin φ φ ˙ = 2 v m tan δ f / L
Obviously, due to the constraint between the front and rear wheel angle relationship, the SFRWS model limits the steering freedom of 4WS vehicle, which reduces flexibility. For this reason, this paper proposes a predictive control method based on the unconstrained steering model of 4WS.
From the trigonometric function operation, we can get the Equation (4).
tan δ r + tan δ f = tan ( δ f + δ r ) ( 1 tan δ r tan δ f )
We can further simplify the kinematics model because the vehicle turning angle is less than 30°.
tan δ r + tan δ f ( δ f + δ r )
Combining Equations (1) and (5), we can get a simplified non-linear 4WS kinematics model unrestrained on the front and the rear wheel steering relationship (UFRWS). The model is as follows:
X ˙ = V cos ( ψ + δ r + δ f 2 ) Y ˙ = V sin ( ψ + δ r + δ f 2 ) ψ ˙ = V cos δ r + δ f 2 f + r δ f δ r

3. Optimal Predictive Control Based Different Model

In this section, the objective functions and constraints of system control quantity optimization are designed based on the UFRWS model and SFRWS model. The optimization problem is solved in the form of a constrained quadratic programming and rolling optimization is performed.

3.1. Linear Discrete Tracking Error Model Based UFRWS Model

We define the state vector χ = [ e x e y e φ ] T , the control input u = [ δ f δ r ] T , where the error e x is the difference between the actual position of the vehicle and the reference position in the X direction, the error e y is in the Y direction, and the heading error e φ is the difference between the vehicle heading angle and the reference heading angle. Then, the tracking error model based on UFRWS model can be obtained.
χ ˙ = e ˙ x e ˙ y e ˙ φ = X ˙ X ˙ r e f Y ˙ Y ˙ r e f φ ˙ φ ˙ r e f = f ( χ , u )
Since the reference points are all on the reference trajectory, Equation (7) can be expanded by the first-order Taylor expansion at the reference state quantity χ r e f = [ 0 0 0 ] T , and we can get:
χ ˙ = f ( χ , u ) χ χ = χ r e f , u = u r e f χ χ r e f + f ( χ , u ) u χ = χ r e f , u = u r e f u u r e f
Based on the Jacobi matrix, the state space form of the linear tracking error model can be developed as follows:
χ ˙ = A χ + B u + W η = C χ ,
where η is the state transition matrix, C is the 3 × 3 identity matrix.
Discretizing the continuous system Equation (9) by using the forward Euler method can obtain a linear discrete tracking error model Equation (10).
χ ( k + 1 ) = A d χ ( k ) + B d u ( k ) + W d ,
Where A d = I + A T = 1 0 T v r e f sin φ r e f + β r e f 0 1 T v r e f cos φ r e f + β r e f 0 0 1 , B d = B T = 1 2 T v r e f sin φ r e f + β r e f 1 2 T v r e f sin φ r e f + β r e f 1 2 T v r e f cos φ r e f + β r e f 1 2 T v r e f cos φ r e f + β r e f T v r e f s i n β r e f δ f δ r c o s β r e f 2 L T v r e f s i n β r e f δ f δ r + c o s β r e f 2 L , W d = W T = 1 2 v r e f sin φ r e f + β r e f ( δ f + δ r ) T 1 2 v r e f cos φ r e f + β r e f ( δ f + δ r ) T 1 2 δ f v r e f ( sin β r e f ( δ f δ r ) c o s β r e f ) T / L + 1 2 δ r v r e f ( sin β r e f ( δ f δ r ) + c o s β r e f ) T / L .

3.2. Linear Discrete Tracking Error Model Based SFRWS Model

Different from the UFRWS-based model, the control input of the SFRWS-based system is only the front wheel angle, that is u = δ f . In the same way, the discretization model based SFRWS model can be obtained as follows:
χ ( k + 1 ) = A d χ ( k ) + B d u ( k ) + W d ,
where A d = 1 0 T v r e f sin φ r e f 0 1 T v r e f cos φ r e f 0 0 1 , B d = 0 0 T v r e f L cos 2 δ f , W d = W T = 0 0 T v r e f δ f L cos 2 δ f .

3.3. State Prediction Model

According to Equation (11), the state quantity at each moment can be predicted.
χ ( k + 1 k ) = A d χ ( k ) + B d u ( k ) + W d χ ( k + 2 k ) = A d 2 χ ( k ) + A d B d u ( k ) + B d u ( k + 1 ) + A d W d + W d χ ( k + 3 k ) = A d 3 χ ( k ) + A d 2 B d u ( k ) + A d B d u ( k + 1 ) + B d u ( k + 2 ) + A d 2 W d + A d W d + W d χ ( k + N p k ) = A d N p χ ( k ) + A d N p 1 B d u ( k ) + + A d N p N c 1 B d u ( k + N c ) + A d N P 1 W d + + A d N p N p W d
Then, the state prediction equation is:
Y ( k ) = Ψ χ ( k ) + Θ U ( k ) + W e ,
where Y ( k ) = η ( k + 1 k ) η ( k + 2 k ) η ( k + 3 k ) η ( k + N p k ) , U ( k ) = u ( k k ) u ( k + 1 k ) u ( k + 2 k ) u ( k + N c k ) , Ψ = C A d C A d 2 C A d 3 C A d N p ,
Θ = C B d C A d B d C B d C A d 2 B d C A d B d C B d C A d N p 1 B d C A d N p 2 B d C A d N p N c 1 B d W e = C W d C A d W d + C W d C A d 2 W d + C A d W d + C W d C A d k 1 W d + C A d k 2 W d + + C W d .

3.4. Scrolling Optimization

The control goal of the system is to make the 4WS vehicle track the target trajectory quickly and stably. Therefore, it is necessary to optimize the state quantity of the system, the control quantity, and the amount of change in the control quantity.
At the k moment, the amount of change in the control quantity is defined as:
Δ u ( k ) = u ( k ) u ( k 1 ) .
Then:
Δ U ( k ) = Δ u ( k ) Δ u ( k + 1 ) Δ u ( k + N c ) = 1 1 1 1 1 1 U = D U .
The design objective function is as follows:
J ( k ) = i = 1 N p χ ( k + i ) Q 2 + i = 1 N c 1 U ( k + i ) U r e f ( k + i ) R 1 2 + i = 1 N c 1 Δ U ( k + i ) Δ R 2 ,
where the first part is to make the current state error that is the lateral error and heading error close to 0. The importance of each state quantity can be adjusted by changing the weight value in the matrix R . The second part is to minimize the error between the control quantity and the reference value. The weight of each control variable can be set by adjusting the weight value in the matrix R 1 . The third part is to make the change of the control variable as small as possible to reduce the output angular velocity value. The parameters and weights can be set by adjusting the matrix Δ R .
This paper mainly considers the control quantity limit constraint and control increment constraint in the control process. The expression form of the control quantity is as follows:
u min ( k ) u ( k ) u min ( k ) , k = 0 , 1 , , N c 1 ,
The expression for the control increment is as follows:
Δ u min ( k )   Δ u ( k ) Δ u min ( k ) , k = 0 , 1 , , N c 1 ,
Define E = Φ X 0 + W , R 2 = D T Δ R D . After simplifying, the cost function is transformed into a standard format for quadratic objective functions with linear constraints.
min J = 1 2 U T H U + f T U s t . U min Δ U min < I D U < U max Δ U max
where H = Θ T Q Θ + R 1 + R 2 , f = E T Q Θ U r T R 1 T , U min is the lower limit sequence of the angle value u min , U max is the upper limit sequence of the angle value u max , Δ U min is the lower limit sequence of the angle rate value Δ u min , and Δ U max is the upper limit sequence of the angle rate value Δ u max .
In each control cycle, the effective set method is used to solve the Equation (16), then the optimal control sequence in the control time domain is obtained.
U * = u k * u k + 1 * u k + N c 1 *
The first element in the control sequence is used as the actual control input to act on the system. After entering the next cycle, the optimal control sequence is recalculated and the first control increment acts on the control system. So, scrolling realizes the optimal control of vehicle trajectory tracking.

4. Experimental Results and Discussion

This article establishes a high-fidelity dynamic model in Carsim based on four-wheel steer-by-wire vehicle, which forms a joint platform with Simulink for simulation experiments. After that, real vehicle trajectory tracking experiments were carried out. The Pure Pursuit based on the SFRWS (PP-SFRWS) model tracking method, the Model Predict Control based on the SFRWS (MPC-SFRWS) model, and the Model Predict Control based on the model unconstrained the front and the rear wheels steering (MPC-UFRWS) are compared and verified.

4.1. 4WS Vehicle Experiment Platform

The electrical system for the four-wheel steer-by-wire chassis used in the experiment is as shown in Figure 4. The system has dual motors and two steer-by-wire modules to control the rotation and steering of front and rear wheels respectively. So, the 4WS vehicle has more freedom degrees used for attitude control. A combined positioning system uses Global Positioning System (GPS) and Inertial Navigation System (INS). The upper computer is used to monitor and collect data from the controller area network (CAN). All control algorithms code is downloaded to the ECU and run in the ECU.
The main structural parameters of 4WS AGV are shown in Table 1.
The vehicle drive control topology can be divided into the chassis domain and the autonomous driving domain as shown in Figure 5. The vehicle control unit (VCU) communicate with the motor control unit (MCU), the steering by wire (SBW), the electrical hydraulic brake (EHB), the electric park brake (EPB), the battery management system (BMS), and instrument electronic control unit (I-ECU) through the CAN bus to obtain the information of the remote control, the automatic driving domain computer (Industrial Personal Computer, IPC), and the parallel driving controller.
In the trajectory tracking control system established in this paper, lidar is mainly used to establish point cloud map and positioning. As shown in Figure 6, the acquisition of vehicle pose in this paper mainly relies on the fusion positioning system composed of lidar and GNSS-RTK.
When the vehicle starts outdoors, the navigation system is initialized with the GNSS-RTK information at the starting point. When the IMU data are received, the state variables of navigation system (position, speed, attitude, etc.) are updated recursively, and the recursive prediction is calculated to represent the uncertainty of the error state. When the LIDAR point cloud is received, the local map is used for registration, and the pose information of the vehicle relative to the local map is obtained. Taking the pose information as the observation, the new error state quantity and the filter gain are calculated. The parameters of the navigation module are modified according to the filter gain to realize the data fusion between IMU and LIDAR. As a result, vehicle pose is generated accurately and output to the control module.

4.2. Simulation Platform Construction

Based on the vehicle parameters of the experimental platform, a vehicle dynamics simulation model is established in Carsim, where the road adhesion coefficient is set to 0.8, and the rolling resistance coefficient is set to 0.8. The trajectory tracking controller is built by the S-function module in Simulink. A co-simulation platform is established with Carsim as shown in Figure 7.
In the vehicle trajectory tracking simulation, the double lane change maneuver is a commonly used reference trajectory in the trajectory tracking test. In this paper, the function equation of the double lane change trajectory used in the simulation is as follows
Y r e f ( X ) = d y 1 2 ( 1 + tanh ( z 1 ) ) d y 2 2 ( 1 + tanh ( z 2 ) ) φ r e f ( X ) = tan 1 ( d y 1 1 cosh z 1 2 1.2 d x 1 d y 2 1 cosh z 2 2 1.2 d x 2 )
where z 1 = 2.4 25 ( X 27.19 ) 1.2 , z 2 = 2.4 21.95 ( X 56.46 ) 1.2 , d x 1 =   25 , d x 2 =   21.95 , d y 1 =   4.05 , d y 2 =   5.7 .

4.3. Analysis of Simulation Results

The simulation and real vehicle verification results are represented based on the trajectory of the vehicle’s geometric center point. As shown in Figure 8a,b, the MPC-UFRSS method has better tracking performance for double lane change maneuver. At a speed of 5 m/s, the maximum lateral tracking error of the MPC-UFRWS method does not exceed 0.01 m, with 0.03 m for the SFRSW method and 0.1 m for the PP-SFRSW method.
As shown in Figure 8c, the PP-SFRSW method has the hard constraint between the front and rear wheels that the equal steering angles and opposite phase, while the MPC-UFRWS does not have this limitation. Therefore, the latter steering control changes are more flexible in corners, and the front and rear wheels steering forms are more diverse. As shown in Figure 8, when the vehicle enters the curve, the MPC-UFRWS method is relatively gentle, while the lateral tracking error of the PP-SFRSW increases sharply. The front and rear wheels angle adjustment of the MPC-UFRWS is larger, which can respond to the change of tracking error faster and track reference trajectory more flexibly.

4.4. Simulation Comparison at Different Speeds

The trajectory tracking of the MPC-UFRWS method comparison at different speeds is as shown in Figure 9. The greater speed, the greater the control error and the greater the overshoot. Similar to other methods based on the kinematics model, the proposed method is suitable for low-speed conditions. When the speed is less than 5 m/s, the lateral tracking error is less than 0.01 m. When the speed is 10 m/s, the lateral tracking error is greater than 0.06 m. However, when the speed is 15 m/s, the vehicle path deviates far from the reference path.

4.5. Analysis of Real Vehicle Verification Results

To ensure the safety of personnel and vehicles, the vehicle experiment was carried out in an open space of Sun Yat-sen University. To verify the performance of the vehicle tracking straight and curved lines at the same time, we choose a recorded B-like trajectory as the reference trajectory considering the site constraints. The test site and vehicle are as shown in Figure 10.
The real vehicle verification results of MPC-UFRWS, PP-SFRWS, and MPC-SFRWS are as shown in Figure 11 and Table 2, and analysis are as follows:
  • Compared with the PP-SFRWS method, the trajectory tracking accuracy of the MPC-UFRSW is higher. At the speed of 2 m/s, the maximum lateral error and yaw angle error are reduced by 0.567 m and 5.55°, respectively. This is because the Pure Pursuit method only determines the control input based on the deviation of the current measured values from the reference value, while the MPC method uses the prediction model to estimate the future deviation value and determine the current values in a rolling optimization manner.
  • The MPC-UFRWS method has higher tracking accuracy than the MPC-SRFRS. At a speed of 2 m/s, the maximum lateral error and yaw angle error are reduced by 0.15 m and 0.5°, respectively. This is because MPC-UFRWS does not constrain the relationship between the front and rear wheels angle, which can give full play to the more flexible characteristics of 4WS vehicle and avoid oversteering or understeering.
  • The proposed method enables better steering flexibility of 4WS vehicle. At the starting point, the lateral error between the vehicle and the reference trajectory is about 2.5 m. When the vehicle starts to drive, the MPC-URFSW method makes the vehicle merge into the trajectory in an approximate crab-walking manner, while the front and rear wheels turn in phase or out of phase in the corners. Therefore, the proposed method can realize the switching of various steering modes such as out-of-phase steering and crab steering without adding additional judgment.
  • Compared with the simulation results, the real vehicle tracking error increases several times. The reason may be that the curvature change rate of the B-like rail is larger than the double lane change maneuver. At the same time, external factors such as actuators, sensors, and road surfaces may also cause large tracking errors during vehicle verification.

5. Conclusions

In this paper, a path tracking controller with unconstrained front and rear wheels steering is established for the trajectory tracking control of 4WS vehicle. The controller relies on the proposed optimization function considering the tracking accuracy and control flexibility. Then, the simulation and vehicle verification are carried out to prove the effectiveness of the controller. In the Carsim/Simulink platform, MPC-UFRSW has higher tracking accuracy than PP-SFRSW and MPC-SFRSW when tracking double lane change trajectory at a speed not exceeding 10 m/s. In the real vehicle experiment with B-like curve, the steering angle of the front and rear wheels of the proposed controller changes more flexibly. The maximum lateral error and yaw angle error are reduced by 60% and 9%, respectively. The simulation and real vehicle verification results show that the proposed method has more flexible steering modes and higher tracking accuracy. The next work will further analyze the stability of the trajectory tracking of the 4WS vehicle at high speed from the dynamic point of view.

Author Contributions

Conceptualization, X.T. and D.L.; methodology, H.X.; validation, D.L., X.T. and H.X.; investigation, D.L.; data curation, D.L.; writing—original draft preparation, X.T. and D.L.; writing—review and editing, H.X.; visualization, D.L.; project administration, H.X. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the Natural Science and Technology Special Projects under Grant 2019-1496, Southern Marine Science and Engineering Guangdong Laboratory (Zhuhai) under Grant SML2020SP011, and the Key-Area Research and Development Program of Guangdong Province under Grant 2020B090921003.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Detailed data are contained within the article. More data that support the findings of this study are available from the author D.L. upon reasonable request.

Acknowledgments

The authors are thankful for the support of the School of Intelligent Systems Engineering, Sun Yat-sen University, China Nuclear Power Engineering Co., Ltd., and Southern Marine Science and Engineering Guangdong Laboratory. At the same time, we thank Guohui Wu and Yuelong Pan for their help in the experiment and writing.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Paden, B.; Cap, M.; Yong, S.Z.; Yershov, D.; Frazzoli, E. A Survey of Motion Planning and Control Techniques for Self-Driving Urban Vehicles. IEEE Trans. Intell. Veh. 2016, 1, 33–55. [Google Scholar] [CrossRef] [Green Version]
  2. Hang, P.; Chen, X. Path tracking control of 4-wheel-steering autonomous ground vehicles based on linear parameter-varying system with experimental verification. Proc. Inst. Mech. Eng. Part I J. Syst. Control. Eng. 2021, 235, 411–423. [Google Scholar] [CrossRef]
  3. Cui, Q.; Ding, R.; Wei, C.; Zhou, B. Path-tracking and lateral stabilisation for autonomous vehicles by using the steering angle envelope. Veh. Syst. Dyn. 2020, 59, 1672–1696. [Google Scholar] [CrossRef]
  4. Coulter, R. Implementation of the Pure Pursuit Path Tracking Algorithm. Carnegie-Mellon UNIV Pittsburgh PA Robotics INST, 1992; p. CM U-RI-TR-92-01. [Google Scholar]
  5. Thrun, S.; Montemerlo, M.; Dahlkamp, H.; Stavens, D.; Aron, A.; Diebel, J.; Fong, P.; Gale, J.; Halpenny, M.; Hoffmann, G.; et al. Stanley: The robot that won the DARPA Grand Challenge. J. Field Robot. 2006, 23, 661–692. [Google Scholar] [CrossRef]
  6. Hiraoka, T.; Nishihara, O.; Kumamoto, H. Automatic path-tracking controller of a four-wheel steering vehicle. Veh. Syst. Dyn. 2009, 47, 1205–1227. [Google Scholar] [CrossRef]
  7. Jiang, Z.; Xiao, B. LQR optimal control research for four-wheel steering forklift based-on state feedback. J. Mech. Sci. Technol. 2018, 32, 2789–2801. [Google Scholar] [CrossRef]
  8. Park, M.; Kang, Y. Experimental Verification of a Drift Controller for Autonomous Vehicle Tracking: A Circular Trajectory Using LQR Method. Int. J. Control Autom. Syst. 2021, 19, 404–416. [Google Scholar] [CrossRef]
  9. Falcone, P.; Borrelli, F.; Asgari, J.; Tseng, H.E.; Hrovat, D. Predictive Active Steering Control for Autonomous Vehicle Systems. IEEE Trans. Contr. Syst. Technol. 2007, 15, 566–580. [Google Scholar] [CrossRef]
  10. Kabzan, J.; Hewing, L.; Liniger, A.; Zeilinger, M.N. Learning-based Model Predictive Control for Autonomous Racing. IEEE Robot. Autom. Lett. 2019, 4, 3363–3370. [Google Scholar] [CrossRef] [Green Version]
  11. Geng, K.; Chulin, N.A.; Wang, Z. Fault-Tolerant Model Predictive Control Algorithm for Path Tracking of Autonomous Vehicle. Sensors 2020, 20, 4245. [Google Scholar] [CrossRef] [PubMed]
  12. Jiang, J.; Astolfi, A. Lateral Control of an Autonomous Vehicle. IEEE Trans. Intell. Veh. 2018, 3, 228–237. [Google Scholar] [CrossRef] [Green Version]
  13. Furukawa, Y.; Yuhara, N.; Sano, S.; Takeda, H.; Matsushita, Y. A Review of Four-Wheel Steering Studies from the Viewpoint of Vehicle Dynamics and Control. Veh. Syst. Dyn. 1989, 18, 151–186. [Google Scholar] [CrossRef]
  14. Oksanen, T.; Backman, J. Guidance system for agricultural tractor with four wheel steering. IFAC Proc. Vol. 2013, 46, 124–129. [Google Scholar] [CrossRef] [Green Version]
  15. Yan, Y.; Geng, K.; Liu, S.; Ren, Y. A New Path Tracking Algorithm for Four-Wheel Differential Steering Vehicle. In Proceedings of the 2019 Chinese Control and Decision Conference (CCDC), Nanchang, China, 3–5 June 2019; pp. 1527–1532. [Google Scholar]
  16. Liang, Y.; Li, Y.; Zheng, L.; Yu, Y.; Ren, Y. Yaw rate tracking-based path-following control for four-wheel independent driving and four-wheel independent steering autonomous vehicles considering the coordination with dynamics stability. Proc. Inst. Mech. Eng. Part D J. Automob. Eng. 2021, 235, 260–272. [Google Scholar] [CrossRef]
  17. Hang, P.; Chen, X. Towards Autonomous Driving: Review and Perspectives on Configuration and Control of Four-Wheel Independent Drive/Steering Electric Vehicles. Actuators 2021, 10, 184. [Google Scholar] [CrossRef]
  18. Ye, Y.; He, L.; Zhang, Q. Steering Control Strategies for a Four-Wheel-Independent-Steering Bin Managing Robot. IFAC-PapersOnLine 2016, 49, 39–44. [Google Scholar] [CrossRef]
  19. Wu, Y.; Li, B.; Zhang, N.; Du, H.; Zhang, B. Rear-Steering Based Decentralized Control of Four-Wheel Steering Vehicle. IEEE Trans. Veh. Technol. 2020, 69, 10899–10913. [Google Scholar] [CrossRef]
  20. Yin, D.; Wang, J.; Du, J.; Chen, G.; Hu, J.-S. A New Torque Distribution Control for Four-Wheel Independent-Drive Electric Vehicles. Actuators 2021, 10, 122. [Google Scholar] [CrossRef]
  21. Fnadi, M.; Plumet, F.; Benamar, F. Model Predictive Control based Dynamic Path Tracking of a Four-Wheel Steering Mobile Robot. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Macau, China, 3–8 November 2019. [Google Scholar]
Figure 1. Trajectory tracking controller framework diagram.
Figure 1. Trajectory tracking controller framework diagram.
Actuators 11 00061 g001
Figure 2. Schematic diagram of relevant variables of 4WS vehicle kinematics model.
Figure 2. Schematic diagram of relevant variables of 4WS vehicle kinematics model.
Actuators 11 00061 g002
Figure 3. Schematic diagram of the SFRWS kinematics model of the 4WS vehicle.
Figure 3. Schematic diagram of the SFRWS kinematics model of the 4WS vehicle.
Actuators 11 00061 g003
Figure 4. Steer-by-wire electrical system for Chassis of 4WS vehicle.
Figure 4. Steer-by-wire electrical system for Chassis of 4WS vehicle.
Actuators 11 00061 g004
Figure 5. The software architecture of the chassis platform.
Figure 5. The software architecture of the chassis platform.
Actuators 11 00061 g005
Figure 6. The location system framework.
Figure 6. The location system framework.
Actuators 11 00061 g006
Figure 7. Carsim/Simulink co-simulation platform.
Figure 7. Carsim/Simulink co-simulation platform.
Actuators 11 00061 g007
Figure 8. Simulation results of different algorithms. (a) Trajectory tracking; (b) Lateral error; (c) Steering angle.
Figure 8. Simulation results of different algorithms. (a) Trajectory tracking; (b) Lateral error; (c) Steering angle.
Actuators 11 00061 g008
Figure 9. Tracking comparison at a different speed. (a) Trajectory tracking; (b) Lateral error.
Figure 9. Tracking comparison at a different speed. (a) Trajectory tracking; (b) Lateral error.
Actuators 11 00061 g009
Figure 10. Experimental site and vehicle.
Figure 10. Experimental site and vehicle.
Actuators 11 00061 g010
Figure 11. Results of different methods in vehicle experiments. (a) Trajectory tracking; (b) Lateral error; (c) Heading error; (d) Steering angle.
Figure 11. Results of different methods in vehicle experiments. (a) Trajectory tracking; (b) Lateral error; (c) Heading error; (d) Steering angle.
Actuators 11 00061 g011aActuators 11 00061 g011b
Table 1. Vehicle parameters.
Table 1. Vehicle parameters.
ParametersSymbolValueUnit
The quality of the whole vehicle m 700kg
Wheelbase L 1.9m
Wheel track W 1.2m
Maximum steering angle δ max 30°/s
Maximum steering angle rate Δ δ max 20°/s
Table 2. Result data of vehicle verification.
Table 2. Result data of vehicle verification.
MethodMax LatErrMaxYawErrstdPLatErrstdPYawErr
PP-SFRWS0.766312.28290.31683.4911
MPC-SFRWS0.34887.28500.12021.7169
MPC-UFRWS0.19986.73540.06782.6064
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Tan, X.; Liu, D.; Xiong, H. Optimal Control Method of Path Tracking for Four-Wheel Steering Vehicles. Actuators 2022, 11, 61. https://doi.org/10.3390/act11020061

AMA Style

Tan X, Liu D, Xiong H. Optimal Control Method of Path Tracking for Four-Wheel Steering Vehicles. Actuators. 2022; 11(2):61. https://doi.org/10.3390/act11020061

Chicago/Turabian Style

Tan, Xiaojun, Deliang Liu, and Huiyuan Xiong. 2022. "Optimal Control Method of Path Tracking for Four-Wheel Steering Vehicles" Actuators 11, no. 2: 61. https://doi.org/10.3390/act11020061

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop