Next Article in Journal
Comparative Analysis of the Self-Propelled Locomotion of a Pitching Airfoil near the Flat and Wavy Ground
Previous Article in Journal
In-Situ Surface Modification of ITO Substrate via Bio-Inspired Mussel Chemistry for Organic Memory Devices
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Research on Six-Wheel Distributed Unmanned Vehicle Path Tracking Strategy Based on Hierarchical Control

1
College of Intelligent Science, National University of Defense Technology, Changsha 410073, China
2
College of Automation Engineering, Nanjing University of Aeronautics and Astronautics, Nanjing 211106, China
3
Chongqing Chang’an Wangjiang Industry Company Limited, Chongqing 404135, China
*
Author to whom correspondence should be addressed.
Biomimetics 2022, 7(4), 238; https://doi.org/10.3390/biomimetics7040238
Submission received: 30 August 2022 / Revised: 29 November 2022 / Accepted: 1 December 2022 / Published: 12 December 2022

Abstract

:
For the multi-objective control problem of tracking effect and vehicle stability in the path tracking process of six-wheel distributed unmanned vehicles, a control strategy based on hierarchical control (HC) theory is proposed. A hierarchical kinematic model is designed considering the structural advantages of independent steering and independent driving of the unmanned vehicle, and this model is applied to the path tracking strategy. The strategy is divided into two levels of control. The upper level of control is to use the upper-level kinematic model as the prediction model of model predictive control (MPC), and to convert the solution problem of future control increments into the optimal solution problem of quadratic programming by setting the optimal objective function and constraints. The lower level of control is to map the optimal control quantities obtained from the upper level control to the six-wheel speeds and the four-wheel turning angles through the lower-level kinematics, and to design the six-wheel torque distribution rules based on deterministic torque and stability-based slip rate control for executing the control requirements of the upper level controller to prevent the unmanned vehicle from generating sideslip and precisely generating transverse moment to ensure the stable driving of the unmanned vehicle. Experiments were conducted on the Trucksim/Simulink simulation platform for a variety of road conditions, and the results showed that hierarchical control improved the accuracy of tracking the desired path and the driving stability on complex road surfaces more than MPC.

1. Introduction

Unmanned ground vehicles (UGV) are designed with a distributed chassis structure with six-wheel independent drive and four-wheel independent steering (6WID/4WIS) as a platform, with the advantages of fast, flexible and accurate response [1,2,3,4]. Applying it to path tracking control not only improves the accurate tracking of the desired path, but also helps improve the operability and flexibility of unmanned vehicles [5,6]. Scholars at home and abroad have carried out much research on the path tracking control of UGV. The commonly used path tracking control algorithms include PID [7,8], fuzzy control [9,10], model predictive control [11,12,13] and so on.
Zhao et al. have achieved acceptable tracking results based on the PID algorithm for tracking the target heading angle and target position from the path planning level [14,15]. However, the PID control algorithm has several problems: first, the workload of debugging PID control parameters is large; second, the PID control algorithm serves to correct the existing control deviation, and it is difficult to achieve accurate control for unmanned vehicles with large inertia. Zhang et al. proposed an unmanned path-tracking strategy based on fuzzy control and PID. The control strategy uses the fuzzy control theory to determine the desired front wheel heading angle based on lateral deviation, heading deviation and speed, effectively improving the stability of vehicle running and tracking accuracy [16]. You [17] established a pre-target path tracker based on an expert PID algorithm and optimal pre-target control theory, and verified through simulation that the strategy has adequate reliability on a good road surface, but the tracking error is larger on a complex road surface or in low adhesion coefficient road conditions.
Considering the limitations of the PID, many scholars have carried out research on path tracking control based on MPC theory. As a popular feedback control algorithm, MPC is widely used in the industrial production control process [18]. The MPC algorithm is a control method that considers the inputs, outputs and future states of the system and compares them with future reference signals when calculating the optimal control inputs of the system. Given the control signal delay problem existing in PID, MPC adds a prediction model to the control system to predict the future state of the robot, thus avoiding the phenomenon of control lag in PID [19]. Gong and Sun used an integral front-wheel steering vehicle as a research object, and applied kinematic and dynamic models to build a prediction model and performed a quadratic programming solution to improve the accuracy of UGV path tracking on good road surfaces [20,21]. Zhao [22] proposed a preview time adaptive control method for path tracking based on the MPC algorithm and vehicle dynamics model, and used a differential torque control method based on reference heading angle to improve the reliability and accuracy of path tracking under constant torque demand. Wang [23] designed a combined steering and braking path tracking controller based on the MPC algorithm. By linearizing the nonlinear vehicle and tire models, a linear time-varying MPC was designed to improve the real-time performance of the system. Simulation results show that the overall control method had better path tracking performance, less interference between steering and braking, and less influence on the longitudinal motion. Jiang [24,25] proposed a model-free predictive control strategy based on particle swarm optimization (PSO). First, the MFAPC control scheme was improved by integrating vehicle state parameters; then, the main parameters of the improved control scheme were optimized based on the PSO algorithm; finally, the effectiveness of the method under different operating conditions was verified by simulation. Kang [26] designed a six-wheel distributed unmanned vehicle drive control algorithm based on slip steering to determine the torque command on each wheel by determining the optimal longitudinal tire force to keep the slip rate value below the limit and to track the desired tire force. Simulations and tests show that the control method has adequate control performance. Xu [27] proposed an adaptive trajectory tracking control method based on pre-targeting time, which introduces a weighting factor method for differential steering and autonomous steering to achieve coordinated trajectory tracking control for distributed unmanned vehicles with differential and autonomous steering.
Among the available research materials on UGV path-following strategies, the following issues have not been addressed.
(1)
Most researchers have only focused on the improvement of accuracy performance during UGV path tracking control, but ignored the problem of stability during vehicle driving.
(2)
The application of the MPC algorithm for path tracking control causes the problems of long adjustment time and weak anti-interference capability because its calculation is complex and time-consuming, and these problems have not been better solved.
(3)
The state quantities considered by most researchers based on the MPC algorithm are mainly the position and heading angle of the vehicle, which fail to consider and constrain the fluctuation of slip rate and excessive transverse moment caused by the complex road surface, resulting in the instability phenomenon of UGV.
(4)
At present, most scholars mainly study the traditional front-wheel steering or four-wheel independent drive unmanned vehicle—addressing the accuracy and stability issues during path tracking of distributed unmanned ground vehicles (DUGV) with six-wheel independent steering and four-wheel independent steering is not common.
For the multi-objective control problem of tracking accuracy and vehicle stability during DUGV path tracking, a distributed unmanned vehicle coordination control strategy is proposed based on hierarchical control theory. The main components of this work are as follows. (1) A hierarchical kinematic model is proposed based on the advantages of independent driving and independent steering of the six-wheel DUGV. (2) Based on MPC theory, the optimal velocity and angle control quantities are calculated by converting the solution problem of future control increments into the optimal solution problem of quadratic programming by setting the optimal objective function and constraints. (3) We designed the torque distribution rules based on deterministic torque and stability-based slip rate, and (4) conducted Simulink/Trucksim simulations to verify the effectiveness and feasibility of the proposed control strategy for path tracking control of the six-wheel DUGV. This paper is organized as follows: Section 2 introduces the hierarchical kinematic model of path tracking for the 6WID robot; Section 3 proposes a path tracking control strategy based on hierarchical control theory; Section 4 is a simulation test to verify the accuracy and reliability of path tracking of the unmanned vehicle under different working conditions; finally, the contributions of this work are summarized in Section 5.

2. Mathematical Model

The six-wheeled distributed unmanned vehicle is designed with a two-layer path-tracking kinematic model due to the advantages of independent driving and independent steering. The upper kinematic model does not consider the function of independent steering and independent driving of the unmanned vehicle, and only its center-of-mass velocity and front axle center turning angle are analyzed. The lower kinematic model is based on the six-wheel Ackermann steering theory, which maps the center-of-mass velocity and front axle center turning angle to the wheel velocity and turning angle of each of the six wheels to achieve path motion tracking control for distributed unmanned vehicles. The six-wheel distributed unmanned vehicle motion model is shown in Figure 1.

2.1. Upper Layer Kinematic Model

As shown in Figure 2, in the inertial coordinate system OXY, (XG, YG) is the center-of-mass (CoM) coordinate, φ is the heading angle of the unmanned vehicle, θ is the front axle center rotation angle of the unmanned vehicle, V is the CoM velocity of the unmanned vehicle, L is the axis distance and R is the steering radius. The upper kinematic model of the six-wheeled distributed unmanned vehicle is shown in Equation (1).
X ˙ G Y ˙ G φ ˙ = V cos φ V sin φ ω = V cos φ sin φ 0 + V tan θ a 0 0 1

2.2. Lower Kinematic Model

The relationship between the control quantities V and θ about the state quantities [XG, YG, φ] of the six-wheel distributed unmanned vehicle in the path tracking control process is known by the upper-level kinematics. In the lower kinematics, a six-wheel Ackermann steering model is designed based on the two-wheel Ackermann steering model and the function of the distributed unmanned vehicle with six-wheel independent drive and independent steering [28,29]. The model ensures that each wheel makes a circular motion around the same instantaneous center when steering, so that the wheels are in a pure rolling and no-slip state with the ground, to achieve a smooth turn with a smaller steering radius for unmanned vehicles and to maintain better velocity stability and mechanical response characteristics.
Six-wheel Ackermann steering is shown in Figure 1, where B is the wheelbase, L is the axis distance between the front and rear axles and a is the distance from the front axle to the CoM. R L 1 , R L 2 , R L 3 , R R 1 , R R 2 and R R 3 are the steering radii of each wheel center around the center of rotation O. V L 1 , V L 2 , V L 3 , V R 1 , V R 2 , and V R 3 ,are the longitudinal velocities of each wheel. α L 1 , α L 3 , β L 1 and β L 3 are the steering angles of the front and rear axle wheels, respectively. From the above geometric relationships, it can be shown that:
R = a tan θ R L 1 = a 2 + ( R + B 2 ) 2 , R L 1 = a 2 + ( R B 2 ) 2 R L 2 = ( R + B 2 ) , R L 2 = ( R B 2 ) R L 3 = b 2 + ( R + B 2 ) 2 , R L 1 = b 2 + ( R B 2 ) 2
tan α L 1 = a / ( R 1 + B 2 ) , tan α L 3 = b / ( R 2 + B 2 ) tan β L 1 = a / ( R 3 B 2 ) , tan β L 3 = b / ( R 4 B 2 )
From the instantaneous center theorem, it follows that:
V R = V L 1 R L 1 = V L 2 R L 2 = V L 3 R L 3 = V R 1 R R 1 = V R 2 R R 2 = V R 3 R R 3
Equations (2) and (3) are substituted into Equation (4) to obtain the relationship between the longitudinal velocity V i of each wheel about the vehicle velocity V and the front axle center rotation angle θ .
V L 1 = V a 2 + ( R + B 2 ) 2 R = V a 2 + ( R + B 2 ) 2 a tan θ V R 1 = V a 2 + ( R B 2 ) 2 R = V a 2 + ( R B 2 ) 2 a tan θ V L 2 = V ( R + B 2 ) R = V ( a tan θ + B 2 ) a tan θ V R 2 = V ( R B 2 ) R = V ( a tan θ B 2 ) a tan θ V L 3 = V b 2 + ( R + B 2 ) 2 R = V b 2 + ( R + B 2 ) 2 a tan θ V R 3 = V b 2 + ( R B 2 ) 2 R = V b 2 + ( R B 2 ) 2 a tan θ
Based on the above kinematic analysis, the model can realize the mapping of vehicle velocity V and front axle turning angle θ into wheel velocities [ V L 1 , V L 2 , V L 3 , V R 1 , V R 2 , V R 3 ] and turning angles [ α L 1 , α L 3 , β R 1 , β R 3 ] to realize the steering control of a six-wheel distributed unmanned vehicle.

3. Control Design

Based on HC theory and hierarchical kinematic model [30,31,32,33], we propose a distributed unmanned ground vehicle coordination control strategy, which is divided into two layers. In the upper layer control, the upper layer kinematic model is used as the prediction model of MPC, and the solution problem of future control increment is converted to the optimal solution problem of quadratic programming by setting the optimal objective function and constraint conditions. In the lower layer control, the optimal control quantity obtained from the upper layer control is mapped to the velocity of six-wheel and four-wheel turning angles through the lower layer kinematics, and the torque distribution rules based on deterministic torque and stability slip rate are designed to execute the control demand calculated by the upper layer controller to protect the unmanned vehicle from sideslip and precisely generate the demand transverse moment to ensure the stability of the unmanned vehicle driving. The distributed unmanned ground vehicle coordination control strategy is shown in Figure 2.

3.1. Coordinated Control Strategies for Upper Level Design

The MPC controller can predict the future state of the vehicle by establishing a six-wheeled distributed prediction model of the unmanned vehicle and introducing these state quantities into the QP optimization, so as to obtain the optimal control quantity of the unmanned vehicle trajectory tracking [34].

3.1.1. Six-Wheeled Distributed Unmanned Vehicle Prediction Equation

In this paper, the upper kinematics equation of the six-wheel distributed unmanned vehicle is used as the prediction model. According to Formula (1), the model is defined as a control system with input quantity as u v , θ and state quantity as χ x , y , φ , and its form is Equation (2):
χ ˙ = f ( χ , u )
Each trajectory point on the reference trajectory also satisfies the upper kinematic equation, and its form is Equation (7):
χ ˙ r e f = f ( χ r e f , u r e f )
where χ r e f = x r e f y r e f φ r e f T , u r e f = v r e f θ r e f T and r represents the reference volume.
Expanding Equation (6) at the reference trajectory point using the Taylor series and neglecting higher order terms, we obtain:
χ ˙ = f ( χ r e f , u r e f ) + f ( χ , u ) χ χ χ r e f + f ( χ , u ) u u u r e f
The linearized six-wheel distributed unmanned vehicle error model is obtained by subtracting Equation (8) from Equation (7).
χ ˜ ˙ = χ χ r e f = x ˙ y ˙ φ ˙ x ˙ r e f y ˙ r e f φ ˙ r e f = 0 0 v r e f sin φ r e f 0 0 v r e f cos φ r e f 0 0 0 x y φ x r e f y r e f φ r e f + cos φ r e f sin φ r e f tan θ a 0 0 V sec 2 θ a
A discrete linearized state space system is obtained by Euler discretization of the preceding term in Equation (9). The system is based on upper-level kinematics, the basis for designing a six-wheel distributed unmanned vehicle path tracking control strategy based on a linear time-varying model predictive control algorithm [35].
χ ˜ k + 1 = A k , t χ ˜ k + B k , t u ˜ k
where A k , t = 1 0 v r e f sin φ r e f T 0 1 v r e f cos φ r e f T 0 0 1 , B k , t = cos φ r e f T 0 sin φ r e f T 0 tan θ r e f T a v r e f sec 2 θ r e f T a and T is the sampling period.
Convert Equation (10) as follows:
ζ k t = χ ˜ ( k t ) u ˜ ( k 1 t )
to obtain a new state space expression:
ζ k + 1 t = A ˜ k , t ζ k t + B ˜ k , t u ( k t )
where A ˜ k , t = A k , t B k , t 0 m × n I m , B ˜ k , t = B k , t I m , n is the state volume dimension and m is the control volume dimension.
At moment t , the state space equation for the future N p steps of the system is
ζ t + 1 = A ˜ k ζ t + B ˜ k u ( t ) ζ t + 2 = A ˜ k ζ t + 1 + B ˜ k U ( t + 1 ) = A ˜ k A ˜ k ζ t + B ˜ k u ( t ) = A ˜ k 2 ζ t + A ˜ k B ˜ k u ( t ) + B ˜ k u ( t + 1 ) ζ t + 3 = A ˜ k 3 ζ t + A ˜ k 2 B ˜ k u ( t ) + A ˜ k B ˜ k u ( t + 1 ) + B ˜ k u ( t + 2 ) ζ t + N c = A ˜ k N c ζ t + A ˜ k N c 1 B ˜ k u ( t ) + + A ˜ k B ˜ k u ( t + N c 2 ) + B ˜ k u ( t + N c 1 ) ζ t + N p = A ˜ k N p ζ t + A ˜ k N p 1 B ˜ k u ( t ) + + A ˜ k B ˜ k u ( t + N p 2 ) + B ˜ k u ( t + N p 1 )
where N p is the prediction time domain and N c is the control time domain; N p > N c .
At time t , the trajectory state equation of the control system in the predicted time domain is as follows:
Y t = Μ t ζ t + Ω t Δ U t
where Y t = ζ t + 1 t ζ t + 2 t ζ t + N C t ζ t + N P t , Μ t = A ˜ k A ˜ k 2 A ˜ k N c A ˜ k N p , Ω t = B ˜ k 0 0 0 A ˜ k B ˜ k 0 0 A ˜ k N c B ˜ k A ˜ k N c 1 B ˜ k B ˜ k A ˜ k N p B ˜ k A ˜ k N p 1 B ˜ k B ˜ k and U = u ( t ) u ( t + 1 ) u ( t + N c 1 ) u ( t + N p 1 ) .
The analysis of the prediction expression (14) shows that the state quantity ζ k t at the current moment and the control increment U in the predicted time domain can be used to calculate the state quantity and the control output in the predicted time domain to overcome the control delay problem in the PID algorithm.

3.1.2. QP Optimization

U in the prediction expression (14) is unknown, and can only be obtained by setting an appropriate objective function and optimizing the solution. To ensure that the distributed unmanned vehicle can track the desired target path quickly and accurately, we designed an objective function that optimizes the three parameters: state quantity deviation, control quantity and control increment [36].
J ζ t , u t 1 , Δ u t = i = 1 N p ζ t + i t ζ r e f t + i t Q 2 + i = 1 N c u t R 2 + ρ ε 2
where ρ is the weighting factor and ε is the relaxation factor.
The first term reflects the ability of the system to track the reference trajectory, and the second term is the requirement for the control quantity to change smoothly. Q and R are the weight matrices. The whole objective function is to enable the robot to track the desired trajectory quickly and smoothly. In addition, in the robot control system, the control quantity, control increment, and state quantity deviation need to be constrained with the following constraints.
u min t + k u t + k u max t + k Δ u min t + k Δ u t + k Δ u max t + k y min t + k y t + k y max t + k
where k = 0 , 1 , , N c 1 .
The corresponding matrix operation is performed on Formula (14) and Formula (15), and the solution problem of constrained optimization in MPC is equivalent to the following quadratic programming problem [37]:
min Δ U , ε Δ U t T , ε T H t Δ U t T , ε + G t Δ U t T , ε
where H t = Ω t T Q Ω t + R 0 0 ρ , G t = 2 e t T Q Ω t 0 and e t is the tracking error in the predicted time domain.
After the optimal solution of the quadratic programming of Equation (17) is obtained, a series of control incremental inputs Δ U in the control time domain at future moments will be obtained.
Δ U t = u t , Δ u t + 1 , , Δ u t + N c 1
According to the basic principle of MPC, the first element of this control sequence is applied to the system as an actual control input increment.
u t = u t 1 + Δ u
Through the lower kinematics, the actual control quantities obtained from Equation (19) can be mapped to the velocity and steering angle control quantities of the respective wheels of the unmanned vehicle, and the expected wheel torque is calculated by the incremental PID controller. In a new control cycle, the system re-predicts the state quantities in the next time domain based on the current state information, and then obtains a new sequence of control increments through an optimization process.

3.2. Coordinated Control Strategies for Lower Level Design

In the upper level control of unmanned vehicles, the road state information is not taken into account, so it is not always possible to achieve stable and sufficient tracking results when performing path tracking control on complex road surfaces. Therefore, a control strategy based on deterministic torque and adaptive fuzzy PID-based Acceleration Slip Regulation (ASR) is designed in the lower controller. The strategy achieves precise generation of the required yaw moment for control and stabilization of the wheel slip rate by redistributing the torque on each wheel. It ensures the stability of unmanned vehicle driving while satisfying the upper level control requirements.

3.2.1. Distribution Strategy Based on Deterministic Moments

For the six-wheeled distributed unmanned vehicle to maintain the ability to track the desired path, the ideal method is that the yaw moment should be equal to a determined value to avoid all sideslips of the tires, but this method is only effective at low speeds and on good road conditions, and it is impossible to avoid all vehicle sideslips at high speeds and on complex roads [38].
For the advantages of independent drive and independent steering of distributed unmanned vehicles, a new transverse pendulum moment control strategy is proposed in this paper. This strategy distributes the longitudinal wheel moments in such a way as to satisfy the required transverse sway moments for upper level control while keeping the torque difference between individual wheels to a minimum. Its function is to avoid the excessive transverse moment that may cause the unmanned vehicle to skid or oversteer at high speeds or on complex road surfaces, and to achieve the goals of minimizing the error of path tracking accuracy and maintaining vehicle stability.
According to the six-wheel Ackerman steering principle, the longitudinal force of the wheel is equal to the tangential force. To generate the yaw moment required for control, the following wheel driving moment distribution is calculated.
T t o t a l = T L 1 + T L 2 + T L 3 + T R 1 + T R 2 + T R 3 = F L 1 r + F L 2 r + F L 3 r + F R 1 r + F R 2 r + F R 3 r
where T t o t a l is the wheel torque generated by the incremental PID controller after the upper level control, T i is the sum of moments, F i is the driving force of each driving wheel, r is the wheel radius and i = L 1 , L 2 L 3 , R 1 , R 2 R 3 .
Six-wheel distributed unmanned vehicle total transverse moment Μ :
Μ = F L 1 R L 1 + F L 2 R L 2 + F L 3 R L 3 + F R 1 R R 1 + F R 2 R R 1 + F R 3 R R 1 = T L 1 r R L 1 + T L 2 r R L 2 + T L 3 r R L 3 + T R 1 r R R 1 + T R 2 r R R 1 + T R 3 r R R 1
Because T t o t a l and Μ are related to the driving demand, there are multiple solutions for the driving force distribution. To avoid generating too much demand torque causing the unmanned vehicle to lose control in oversteering, our strategy is designed to minimize the difference in torque at each wheel while satisfying the demand transverse swing torque, minimized by the equation:
i = 1 6 T i T t o t a l 6 2
This equation is solved using the Lagrange multiplier method [39].
L T i , λ i = i = 1 6 T i T t o t a l 6 2 + λ 1 i = 1 6 T i T t o t a l + λ 2 i = 1 6 R i T i r Μ
Equation (23) solves the partial differential equation for T i :
L T i , λ i T i = 2 T i + λ 1 + λ 2 R i r T t o t a l 3 = 0
T i = 1 6 T t o t a l 3 λ 1 3 λ 2 R i r
Substituting Equation (25) into Equations (21) and (22), we obtain:
0 = λ 1 + λ 2 R i r
Μ = T t o t a l 6 r R i λ 1 2 r R i λ 2 2 r 2 R i 2
λ is obtained from the joint solution of Equations (26) and (27).
λ 1 = c 1 + d 1 Μ
λ 2 = c 2 + d 2 Μ
where c 1 = T t o t a l 6 , d 1 = r R i , c 2 = T t o t a l r 6 R i and d 2 = r 2 R i 2 .
Substituting Equations (28) and (29) into Equation (27), T i can be expressed by Μ as
T i = Κ i + Ω i Μ
where Κ i = 1 6 T t o t a l 3 c 1 + 3 R i c 2 r and Ω i = R i d 2 2 r d 1 2 .
According to Equation (30), the yaw moment required by the upper control is accurately generated based on the deterministic moment distribution strategy to avoid the instability of the unmanned vehicle caused by over-steering and sideslip.

3.2.2. Adaptive PID-Based Drive Anti-Slip Control

ASR control is a kind of active safety control of automobiles [40]. Its purpose is to obtain the maximum adhesion coefficient by controlling the wheel slip rate, and to avoid the decline in lateral stability caused by excessive wheel slip [41]. The wheel slip rate formula is as follows.
S = V x V V x
where V is vehicle speed and V x is wheel speed. When the wheel rolls purely: V x = V , S = 0 . When the wheel rolls and slides at the same time: V x > V , 0 < S < 100 % . The greater the wheel sliding rate, the greater the proportion of the wheel sliding component in the movement.
In this paper, the method of logical threshold value commonly used in traditional vehicles is used to carry out the drive anti-skid control. The main way is to set the drive anti-skid control threshold, and realize the drive anti-skid control by controlling the real-time slip rate of the wheels. The optimal slip rate is set as 20% [42].
We applied fuzzy control theory based on an incremental PID control algorithm to design an adaptive fuzzy PID controller to achieve the tracking control of the optimal slip rate of the wheel. The controller adjusts the proportional, integral and differential parameters in the incremental PID algorithm online by inputting deviations and the rate of change of deviations to improve the controller’s path tracking performance and enhance the controller’s self-adaptive capability. Adaptive fuzzy PID control is mainly composed of three elements, namely fuzzification, fuzzy inference and clarity, with the corresponding elements input affiliation function, development of control rules and logic judgment [43,44], as shown in Figure 3.
The adaptive fuzzy PID controller takes the difference between the target value of the wheel slip rate and the actual slip rate and the rate of change of the difference as the input of the controller, and adaptively adjusts the parameters Kp, Ki and Kd of the incremental PID by the fuzzy inference method. Equation (32) is the adjustment formula, and the parameter adjustment process is shown in Figure 4.
k p = k p 0 + Δ k p , k i = k i 0 + Δ k i , k d = k d 0 + Δ k d
where k p 0 , k i 0 and k d 0 are the initial parameters of the incremental PID controller; Δ k p , Δ k i and Δ k d are the adjustment parameters of the fuzzy controller output; and k p , k i and k d are the final parameters of the adaptive fuzzy PID controller.

4. Simulation Results

4.1. Distributed Unmanned Vehicle Simulation Platform Based on Trucksim/Simulink

A six-wheeled distributed unmanned vehicle simulation platform with independent drive and independent steering was built jointly with Trucksim and Simulink. The six-wheel distributed unmanned vehicle dynamics model is mainly composed of three parts: body form factor and inertia parameters, vehicle drive/steering system, suspension and tire system. As shown in Figure 5, this paper completes the parameterized models of vehicle form factor, aerodynamics, suspension and tire system in Trucksim, while disconnecting the drive end and steering end interfaces in Trucksim, establishing the drive motor model and steering motor model in Simulink and obtaining the drive torque and steering angle control quantities through the data interfaces in Trucksim.
The data signal interaction with the Trucksim software 2019 was completed in the MATLAB/Simulink environment, integrating six drive motor modules, four steering motor modules, the driver module and the control algorithm module, as shown in Figure 6. The vehicle model parameters are shown in Table 1.
The distributed unmanned vehicle has two-wheel steering, four-wheel steering, four-wheel differential steering, center steering, crabbing, center differential steering and differential steering modes due to its six-wheel independent drive four-wheel independent steering system. The six steering kinematic models are shown in Figure 7.
The above six steering function modes can be realized on the Trucksim/Simulink-based distributed unmanned vehicle simulation platform through wheel speed and turning angle control, as shown in Figure 6, which establishes a simulation platform for a six-wheel independent drive with four-wheel independent steering. Distributed unmanned vehicle path tracking experiments are carried out on the folio and Sine Sweep pavements provided by the simulation platform.

4.2. Split Mu Straight Path Following Experiment

Linear trajectory tracking was carried out on the split road surface at a speed of 40 km/h. The adhesion coefficient of the split road surface was 0.2 on the left side and 0.5 on the right side. The simulation animation is shown in Figure 8. Three methods are used for simulation experiment comparison, namely “no control”, “MPC” and “hierarchical control” designed in this paper, where “no control” refers to no path tracking controller, only including speed controller. “MPC” means that there is no lower control, the upper kinematic model is used as the prediction model of MPC and the optimal control quantity is calculated through the model predictive control theory and directly mapped to the speed control quantity of six wheels and the four-wheel angle control quantity.
Simulation results: Shown in Figure 9 is the trajectory tracking curve. In the case of no control, the unmanned vehicle will gradually drift toward the low adhesion coefficient road surface, and the maximum drift is 1.215. Using the MPC algorithm, due to the inconsistent adhesion coefficient on the left and right side, the longitudinal force that the ground can provide to the wheels is inconsistent, the unmanned vehicle has a long adjustment time and an increasingly large drift with the driving time, and it cannot achieve effective tracking and eventually loses control. After adopting coordinated control, the torque distribution of the wheels based on deterministic torque and slip rate control was carried out, and stable and accurate tracking of the target path was achieved. As shown in Figure 10, in terms of speed tracking, the PID and MPC algorithms reached the target velocity at the same time, but both had steady-state errors, while the coordinated control reached the target velocity 2 s faster than MPC, with a faster response time and no steady-state errors. As shown in Figure 11 and Figure 12, the unmanned vehicle using the MPC algorithm has a large fluctuation in the yaw angle and yaw rate, among which the maximum yaw rate fluctuation reaches −19.48 deg/s to 19.27 deg/s. However, after coordinated control, the vehicle’s yaw rate stabilizes between −1.446 deg/s and 1.548 deg/s. This number is already small enough to satisfy the stable running of unmanned vehicles. Therefore, the coordinated control strategy is more beneficial to the safe driving of the vehicle.
To better test the performance of the control system, simulation tests with vehicle speeds of 20 km/h, 30 km/h, 50 km/h and 60 km/h were conducted. The simulation results were as follows.
As shown in Figure 13 and Figure 14, the unmanned vehicle can track the expected speed of 20 km/h at 1.815 s and can accurately track the target trajectory. The unmanned vehicle can track the desired speed of 30 km/h at 2.511 s and can accurately track the target trajectory. The unmanned vehicle can track the expected speed of 50 km/h at 4.298 s, and achieve accurate tracking of the target track when it travels to 158.9 m. The unmanned vehicle can track the expected speed of 60 km/h at 10.14 s, and achieve accurate tracking of the target trajectory when it travels to 282.1 m. The control system of the unmanned vehicle can maintain the slip rate at 20%, as shown in Figure 15. At this time, the wheels can obtain the maximum adhesion coefficient, which is conducive to the stability control of the unmanned vehicle.

4.3. Sine Sweep Straight Path Following Experiment

Linear trajectory tracking was performed on a Sine sweep road at a velocity of 40 km/h with a road surface adhesion coefficient of 0.85. The simulation animation is shown in Figure 16.
Simulation results: The trajectory tracking curve is shown in Figure 17. Under no control, the unmanned vehicle will gradually shift, and the maximum shift is 2.194. With the MPC algorithm, the unmanned vehicle has a long adjustment time and the actual running trajectory fluctuates between −0.8028 and 0.06908, which cannot achieve effective tracking. After adopting coordination control, there is a small fluctuation in the tracking trajectory in the first 150 m, and after 150 m, accurate tracking of the target path was achieved. As shown in Figure 18, in terms of velocity tracking, the target speed was reached at 13.91 with PID control; with MPC control, the velocity tracking showed overshoot and the target velocity was reached at 17.78 s; with the coordinated control strategy, the accurate tracking of the target velocity was achieved at 5.137 s. As shown in Figure 19, the yaw angle of the unmanned vehicle fluctuated between −6.454 and 5.956 when the MPC algorithm was used. However, after the coordinated control strategy was used, the heading angle of the unmanned vehicle fluctuated slightly and stabilized at 0° after 12 s. As shown in Figure 20, when the MPC algorithm was used, the yaw rate of the unmanned vehicle fluctuated between −8.76 deg/s and 11.13 deg/s, while when the coordinated control strategy was used, the yaw rate of the unmanned vehicle stabilized between −0.7366 deg/s and 0.8099 deg/s after 10 s.
To better test the performance of the algorithm, simulation tests of the vehicle speeds of 20 km/h, 30 km/h, 50 km/h and 60 km/h were conducted on the Sine sweep straight road.
Simulation results: As shown in Figure 21 and Figure 22, when the expected speed is 20 km/h, the speed can reach the expected speed at 2.407 s, and the maximum offset of the trajectory error is 0.07632 m. When the expected speed is 30 km/h, the speed can reach the expected speed at 2.597 s, and the maximum offset of the trajectory error is 0.0128 m. When the expected speed is 50 km/h, the speed can reach the expected speed by 4.226 s, and the maximum offset of the tracking error is 0.2558 m. When the expected speed is 60 km/h, the speed can reach the expected speed at 4.702 s, and the maximum offset of the tracking error is 0.3383 m. Therefore, under different speed conditions, the unmanned vehicle can stably track the target trajectory.
Figure 23 shows the curve of the six-wheel slip rate at 50 km/h. The control system can make the slip rate of the unmanned vehicle stable at 20% in 2 s.
In addition, through the simulation experiments of different speeds under the Split mu straight road and Sine sweep straight road, it was shown that when the unmanned vehicle used the coordinated control strategy for trajectory tracking at low speeds (such as 20 km/h and 30 km/h), it had suitable path tracking performance and accuracy. With the increase in the target speeds of the unmanned vehicle (such as 50 km/h and 60 km/h), the yaw velocity of the vehicle increases with the increase in the vehicle traveling speed, and the yaw torque required by the unmanned vehicle also increases. Therefore, the coordinated control strategy requires longer control convergence time, resulting in the increase in lateral deviation at the initial moment. However, the coordinated control strategy can still accurately track the desired trajectory in a short time to meet the requirements of unmanned vehicle trajectory tracking.

5. Conclusions

(1)
Based on the physical structure of distributed unmanned vehicles with six-wheel independent drive and four-wheel independent steering, we designed a hierarchical kinematic model of unmanned vehicle path tracking based on the six-wheel Ackermann theory.
(2)
Based on HC theory, a coordinated control strategy for path tracking and stability of distributed unmanned vehicles was designed. The strategy is divided into two levels of control. In the upper level of control, the upper kinematic model is used as the prediction model of MPC, and the solution problem of future control increments is converted into the optimal solution problem of quadratic programming by setting the optimal objective function and constraints. The lower level of control is to map the optimal control quantities obtained from the upper level to the six-wheel speed control quantities and the four-wheel turning angle control quantities through the lower-level kinematics, and design the six-wheel torque distribution rules based on deterministic torque and stability-based slip rate control for executing the control demand calculated by the upper-level controller to prevent the unmanned vehicle from producing sideslip and to precisely generate the demand transverse moment to ensure the stability of the unmanned vehicle driving.
(3)
An unmanned vehicle simulation platform based on Trucksim/Simulink with six-wheel independent drive and four-wheel independent steering was established, and the path tracking tests of 20 km/h, 30 km/h, 40 km/h, 50 km/h and 60 km/h were carried out on this platform on the Split mu straight road and the Sine sweep straight road. The simulation results show that the coordinated control has better response characteristics than MPC, which can output the deterministic moment and control the wheel slip rate at 20%, improving the accuracy and stability of the unmanned vehicle path tracking. Therefore, the coordinated control strategy can achieve stable and accurate path tracking under various working conditions.
(4)
In the coordinated control algorithm designed in this paper, there is a coupling relationship between speed tracking and path tracking. In future research, the joint control of the speed and path of the unmanned vehicle will be studied. In addition, the parameters of the vehicle model and control system in this paper are taken as fixed parameters. When the vehicle is under different working conditions, these state parameters have errors with the actual values. The future research direction is to further apply the adaptive control technology to the research of this paper, so that it can have the ability of online update and dynamic change.

Author Contributions

Conceptualization, T.Z. and Y.Y.; methodology, T.Z. and Y.Y.; software, T.Z., Y.Y., H.M. and Y.C.; validation, T.Z. and Y.Y.; formal analysis, T.Z., Y.Y., H.M. and Y.C.; investigation, T.Z. and Y.Y.; resources, T.Z. and Y.Y.; data curation, Y.Y.; writing—original draft preparation, T.Z. and Y.Y.; writing—review and editing, T.Z., Y.Y., H.M. and Y.C.; visualization, T.Z. and Y.Y.; supervision, T.Z.; project administration, T.Z.; funding acquisition, T.Z. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by “Research on the power transmission mechanism of high-smooth small spherical power source and analysis of its working characteristics” (project approval no. 51705525), by “Research on a high-efficiency hydraulic actuator based on imitating the multi-motor unit structure and the control mechanism of human muscles” (project approval no. 51675522) and by “Numerical simulation of the combustion process in the ring working chambers of the Twin-rotor Piston Engine” (project approval no. 2017JJ3355).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Wang, W.; Xu, H.; Xu, X. Enhancing the passing ability of unmanned vehicles using a variable wheelbase driving system. IEEE Access 2019, 7, 115871–115885. [Google Scholar] [CrossRef]
  2. Wang, W.; Xu, X.; Xu, H. Enhancing lateral dynamic performance of all-terrain vehicles using variable wheelbase chassis. Adv. Mech. Eng. 2020, 12, 1–19. [Google Scholar] [CrossRef]
  3. Zhu, J.; Wang, Z.; Zhang, L.; Dorrell, D. Braking/steering coordination control for in-wheel motor drive electric vehicles based on nonlinear model predictive control. Mech. Mach. Theory 2019, 142, 103586–103603. [Google Scholar] [CrossRef]
  4. Chen, L.; Zhang, J.; Li, Y.; Yuan, Y. Directional-stability-aware brake blending control synthesis for over-actuated electric vehicles during straight-line deceleration, Mechatronics 2016, 38, 121–131. Mechatronics 2016, 38, 121–131. [Google Scholar] [CrossRef]
  5. Zhou, F.; Qin, Y.; You, Y.; ZOU, T.; Li, G.; Zhang, Z.; Chang, Y. Distributed electric car path following layered coordination control method research. Mech. Sci. Technol. 2022, 22, 1–10. [Google Scholar]
  6. Liu, M.; You, Y.; Zhou, F. Simulation research on Path Tracking Control of Fully Electric Drive Distributed Unmanned Vehicle. Intell. Comput. Appl. 2022, 12, 61–79. [Google Scholar]
  7. Hossain, T.; Habibullah, H.; Islam, R. Steering and Speed Control System Design for Autonomous Vehicles by Developing an Optimal Hybrid Controller to Track Reference Trajectory. Machines 2022, 10, 420. [Google Scholar] [CrossRef]
  8. Elsisi, M.; Mahmoud, K.; Lehtonen, M.; Darwish, M. An improved neural network algorithm to efficiently track various trajectories of robot manipulator arms. IEEE Access 2021, 9, 11911–11920. [Google Scholar] [CrossRef]
  9. Zhang, H.; Yang, X.; Liang, J.; Xu, X.; Sun, X. GPS Path Tracking Control of Military Unmanned Vehicle Based on Preview Variable Universe Fuzzy Sliding Mode Control. Machines 2021, 9, 304. [Google Scholar] [CrossRef]
  10. Hou, Z.G.; Zou, A.M.; Long, C.; Min, T. Adaptive control of an electrically driven nonholonomic mobile robot via backstepping and fuzzy approach. IEEE Trans. Control Syst. Technol. 2009, 17, 803–815. [Google Scholar] [CrossRef]
  11. You, Y.; Yang, Z.; Zou, T.; Sui, Y.; Xu, C.; Zhang, C.; Xu, H.; Zhang, Z.; Han, J. A New Trajectory Tracking Control Method for Fully Electrically Driven Quadruped Robot. Machines 2022, 10, 292. [Google Scholar] [CrossRef]
  12. Huang, S.; Lin, Y. Simulation-based performance evaluation of model predictive control for building energy systems. Appl. Energy 2021, 281, 116027. [Google Scholar] [CrossRef]
  13. Guo, H.; Cao, D.; Chen, H.; Sun, Z.; Hu, Y. Model predictive path following control for autonomous cars considering a measurable disturbance: Implementation, testing, and verification. Mech. Syst. Signal Process. 2019, 118, 41–60. [Google Scholar] [CrossRef]
  14. Jiang, Y.; Gong, J.; Xiong, G. Research on Longitudinal and Horizontal Cooperative Planning Algorithm for Unmanned Vehicle Based on Differential Motion Constraint. Acta Autom. Sin. 2013, 39, 2012–2020. [Google Scholar] [CrossRef]
  15. Zhao, X.; Chen, H. Research on Lateral Control Method for Intelligent Vehicle Path Tracking. Automot. Eng. 2011, 33, 382–387. [Google Scholar]
  16. Zhang, C.; Gao, G.; Zhao, C.; Li, L.; Li, C.; Chen, X. Research on 4WS Agricultural Machine Path Tracking Algorithm Based on Fuzzy Control Pure Tracking Model. Machines 2022, 10, 597. [Google Scholar] [CrossRef]
  17. You, Z. Research on Trajectory Tracking Control of Unmanned Vehicle Based on MPC Algorithm; Jilin University: Changchun, China, 2018. [Google Scholar]
  18. Hoang, G.; Kim, H.K.; Kim, S.B. Path tracking controller of quadruped robot for obstacle avoidance using potential functions method. Int. J. Sci. Eng. 2013, 4, 1–5. [Google Scholar] [CrossRef]
  19. Dini, N.; Majd, V. An MPC-based two-dimensional push recovery of a quadruped robot in trotting gait using its reduced virtual model. Mech. Mach. Theory 2019, 146, 1–25. [Google Scholar] [CrossRef]
  20. Gong, J.; Xu, W.; Jiang, Y. Multiconstrained Model Predictive Control for Autonomous Ground Vehicle Trajectory Tracking. J. Beijing Inst. Technol. 2015, 24, 441–448. [Google Scholar] [CrossRef]
  21. Sun, Y. Research on Trajectory Tracking Control of Unmanned Vehicle Based on Model Predictive Control; Beijing Institute of Technology: Beijing, China, 2015. [Google Scholar]
  22. Zhao, T.; Xing, X.; Feng, W. Coordinated control for path following of two-wheel independently actuated autonomous ground vehicle. Intell. Transp. Syst. Iet 2019, 13, 628–635. [Google Scholar] [CrossRef]
  23. Wang, G.; Liu, L.; Meng, Y.; Gu, Q.; Bai, G. Integrated path tracking control of steering and braking based on holistic MPC. IFAC-Pap. 2021, 54, 45–50. [Google Scholar] [CrossRef]
  24. Jiang, Y.; Xu, X.; Zhang, L.; Zou, T. Model free predictive path tracking control of variable-configuration unmanned ground vehicle. ISA Trans. 2022, 38, 1–7. [Google Scholar] [CrossRef] [PubMed]
  25. Jiang, Y.; Xu, X.; Zhang, L. Heading tracking of 6wid/4wis unmanned ground vehicles with variable wheelbase based on model free adaptive control. Mech. Syst. Signal Process. 2021, 159, 107715–107725. [Google Scholar] [CrossRef]
  26. Kang, J.; Kim, W.; Lee, J.; Yi, K. Design, implementation, and test of skid steering-based autonomous driving controller for a robotic vehicle with articulated suspension. J. Mech. Sci. Technol. 2010, 24, 793–800. [Google Scholar] [CrossRef]
  27. Xu, X.; Lu, S.; Chen, L.; Cai, Y.; Li, Y. Distributed drive based on differential and independent to coordinate unmanned vehicle trajectory tracking. J. Automob. Eng. 2018, 40, 475–481. [Google Scholar]
  28. Min, W.; Park, J.; Lee, B.; Man, H. The performance of independent wheels steering vehicle(4WS) applied Ackerman geometry. In Proceedings of the International Conference on Control, Seoul, Republic of Korea, 14–17 October 2008; pp. 197–202. [Google Scholar] [CrossRef]
  29. Economou, J.; Luk, P.; Tsourdos, A.; White, B. Hybrid modelling of an all-electric front-wheel Ackerman steered vehicle. In Proceedings of the Vehicular Technology Conference VTC 2003-Fall, Orlando, FL, USA, 6–9 October 2003; Volume 5, pp. 3294–3298. [Google Scholar] [CrossRef]
  30. Wang, Y.; Gao, J.; Li, K.; Chen, H. Integrated design of control allocation and triple-step control for over-actuated electric ground vehicles with actuator faults. J. Frankl. Inst. 2019, 357, 3150–3167. [Google Scholar] [CrossRef]
  31. Jiang, Y.; Meng, H.; Chen, G.; Yang, C.; Xu, X.; Zhang, L.; Xu, H. Differential-steering based path tracking control and energy-saving torque distribution strategy of 6wid unmanned ground vehicle. Energy 2022, 254, 1–15. [Google Scholar] [CrossRef]
  32. Yu, C.; Li, Z.; Tian, S. Straight Running Stability Control Based on Optimal Torque Distribution for a Four in-wheel Motor Drive Electric Vehicle. Energy Procedia 2017, 105, 2825–2830. [Google Scholar] [CrossRef]
  33. Wang, J.; Nan, J.; Xu, X.; Gao, Z.; Qiao, M. Control Strategy and Simulation of Four-wheel-hub Vehicles Torque Distribution on Bisectional Road. Energy Procedia 2017, 105, 2666–2671. [Google Scholar] [CrossRef]
  34. Xu, T.; Ji, X.; Liu, Y. Differential drive-based yaw stabilization using MPC for distributed-drive articulated heavy vehicle. IEEE Access 2020, 8, 104052–104062. [Google Scholar] [CrossRef]
  35. Shi, Y.; He, X.; Zou, W.; Yu, B.; Yuan, L.; Li, M.; Pan, G.; Ba, K. Multi-Objective Optimal Torque Control with Simultaneous Motion and Force Tracking for Hydraulic Quadruped Robots. Machines 2022, 10, 170. [Google Scholar] [CrossRef]
  36. Huang, Y.; Wei, Q.; Ma, H.; An, H. Motion planning for a bounding quadruped robot using ilqg based MPC. J. Phys. Conf. Ser. 2021, 1905, 012016. [Google Scholar] [CrossRef]
  37. Li, J.; Wang, J.; Wang, S. Neural Approximation-based Model Predictive Tracking Control of Non-holonomic Wheel-legged Robots. Int. J. Control. Autom. Systems 2021, 19, 372–381. [Google Scholar] [CrossRef]
  38. Xu, Y.; Yan, J.; Qian, H.; Lin, T. Design and Control of Intelligent Omnidirectional Hybrid Electric Vehicle; China Machine Press: Beijing, China, 2017; pp. 35–41. [Google Scholar]
  39. Liu, J.; Li, H.; Liu, Z. Discussion on Solving extreme Points by Lagrange Multiplier method. Res. Adv. Math. 2017, 20, 13–17. [Google Scholar] [CrossRef]
  40. Wang, Z.; Ding, X.; Zhang, L. Review on key technologies of anti-skid control for electric vehicle driven by four-wheel hub motor. J. Mech. Eng. 2019, 55, 99–120. [Google Scholar]
  41. Chen, L.; Liao, Z.; Zhang, Z. Anti-skid control of multi-wheel wheel motor driven vehicle based on road surface adaptive. Acta Armendarii. 2021, 10, 2278–2290. [Google Scholar]
  42. Feng, Y.; Yang, J.; Ji, Z.; Zhang, W. Control strategy of electric vehicle drive based on Optimal slip rate. Trans. Chin. Soc. Agric. Eng. 2015, 31, 119–125. [Google Scholar] [CrossRef]
  43. Hu, B.; Ying, H. Review of Research and Development of Fuzzy PID Control Technology and Some Important Problems it Faces. Acta Autom. Sin. 2001, 27, 567–584. [Google Scholar] [CrossRef]
  44. Zhang, Q.; Qu, S. Fuzzy PID Implementation of Vehicle Adaptive Cruise Control System. Automot. Eng. 2012, 307, 569–572. [Google Scholar] [CrossRef]
Figure 1. Six-wheel distributed unmanned vehicle path-tracking kinematic model.
Figure 1. Six-wheel distributed unmanned vehicle path-tracking kinematic model.
Biomimetics 07 00238 g001
Figure 2. Coordinated control strategy of the distributed unmanned vehicle with a fully electric drive.
Figure 2. Coordinated control strategy of the distributed unmanned vehicle with a fully electric drive.
Biomimetics 07 00238 g002
Figure 3. Design a fuzzy controller flow diagram.
Figure 3. Design a fuzzy controller flow diagram.
Biomimetics 07 00238 g003
Figure 4. Slip rate controller based on adaptive fuzzy PID.
Figure 4. Slip rate controller based on adaptive fuzzy PID.
Biomimetics 07 00238 g004
Figure 5. Six-wheeled distributed unmanned vehicle dynamics model.
Figure 5. Six-wheeled distributed unmanned vehicle dynamics model.
Biomimetics 07 00238 g005
Figure 6. Simulation module under MATLAB/Simulink.
Figure 6. Simulation module under MATLAB/Simulink.
Biomimetics 07 00238 g006
Figure 7. Six steering motion modes of six-wheel distributed unmanned vehicle: (a) four-wheel Akerman steering; (b) two-wheel Akerman steering; (c) crab walking; (d) differential steering; (e) differential center steering; (f) center steering. The direction of the red arrow is the direction of the wheel movement.
Figure 7. Six steering motion modes of six-wheel distributed unmanned vehicle: (a) four-wheel Akerman steering; (b) two-wheel Akerman steering; (c) crab walking; (d) differential steering; (e) differential center steering; (f) center steering. The direction of the red arrow is the direction of the wheel movement.
Biomimetics 07 00238 g007
Figure 8. Split mu straight road. The yellow arrow represents the force on the wheel in the z-axis direction.
Figure 8. Split mu straight road. The yellow arrow represents the force on the wheel in the z-axis direction.
Biomimetics 07 00238 g008
Figure 9. Path tracking comparison chart on the split mu straight road.
Figure 9. Path tracking comparison chart on the split mu straight road.
Biomimetics 07 00238 g009
Figure 10. Speed tracking comparison chart on the split mu straight road.
Figure 10. Speed tracking comparison chart on the split mu straight road.
Biomimetics 07 00238 g010
Figure 11. Comparison chart of heading angle tracking on the split mu straight road.
Figure 11. Comparison chart of heading angle tracking on the split mu straight road.
Biomimetics 07 00238 g011
Figure 12. Transverse pendulum angular velocity tracking comparison chart on the split mu straight road.
Figure 12. Transverse pendulum angular velocity tracking comparison chart on the split mu straight road.
Biomimetics 07 00238 g012
Figure 13. Speed tracking curves of unmanned vehicles at different speeds on the split mu straight road.
Figure 13. Speed tracking curves of unmanned vehicles at different speeds on the split mu straight road.
Biomimetics 07 00238 g013
Figure 14. Path tracking curves of unmanned vehicles at different speeds on the split mu straight road.
Figure 14. Path tracking curves of unmanned vehicles at different speeds on the split mu straight road.
Biomimetics 07 00238 g014
Figure 15. Wheel slip rate of the distributed unmanned vehicle at 50 km/h on the split mu straight road.
Figure 15. Wheel slip rate of the distributed unmanned vehicle at 50 km/h on the split mu straight road.
Biomimetics 07 00238 g015
Figure 16. Sine sweep straight road. The yellow arrow represents the force on the wheel in the z-axis direction.
Figure 16. Sine sweep straight road. The yellow arrow represents the force on the wheel in the z-axis direction.
Biomimetics 07 00238 g016
Figure 17. Path tracking comparison chart on the sine sweep straight road.
Figure 17. Path tracking comparison chart on the sine sweep straight road.
Biomimetics 07 00238 g017
Figure 18. Speed tracking comparison chart on the sine sweep straight road.
Figure 18. Speed tracking comparison chart on the sine sweep straight road.
Biomimetics 07 00238 g018
Figure 19. Comparison chart of heading angle tracking on the sine sweep straight road.
Figure 19. Comparison chart of heading angle tracking on the sine sweep straight road.
Biomimetics 07 00238 g019
Figure 20. Transverse pendulum angular velocity tracking comparison chart on the Sine sweep straight road.
Figure 20. Transverse pendulum angular velocity tracking comparison chart on the Sine sweep straight road.
Biomimetics 07 00238 g020
Figure 21. Speed tracking curves of unmanned vehicles at different speeds on the sine sweep straight road.
Figure 21. Speed tracking curves of unmanned vehicles at different speeds on the sine sweep straight road.
Biomimetics 07 00238 g021
Figure 22. Path tracking curves of unmanned vehicles at different speeds on the Sine sweep straight road.
Figure 22. Path tracking curves of unmanned vehicles at different speeds on the Sine sweep straight road.
Biomimetics 07 00238 g022
Figure 23. Wheel slip rate of distributed unmanned vehicles at 50 km/h on the sine sweep straight road.
Figure 23. Wheel slip rate of distributed unmanned vehicles at 50 km/h on the sine sweep straight road.
Biomimetics 07 00238 g023
Table 1. The main parameters of 6WID/4WIS UGV.
Table 1. The main parameters of 6WID/4WIS UGV.
ParametersValuesUnits
Sprung mass2900kg
Gravitational acceleration9.8m/s2
The horizontal distance between the center of gravity and the front axle 2m
The horizontal distance between the front axle and the middle axle2.2m
The horizontal distance between the rear axle and middle axle2.2m
Wheelbase2200mm
Height of center of gravity1.25m
Tire diameter0.996m
Tire width0.309m
Power of in-wheel motor65kW
Maximum off-road speed45(km/h)
Sampling period5ms
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Zou, T.; You, Y.; Meng, H.; Chang, Y. Research on Six-Wheel Distributed Unmanned Vehicle Path Tracking Strategy Based on Hierarchical Control. Biomimetics 2022, 7, 238. https://doi.org/10.3390/biomimetics7040238

AMA Style

Zou T, You Y, Meng H, Chang Y. Research on Six-Wheel Distributed Unmanned Vehicle Path Tracking Strategy Based on Hierarchical Control. Biomimetics. 2022; 7(4):238. https://doi.org/10.3390/biomimetics7040238

Chicago/Turabian Style

Zou, Teng’an, Yulong You, Hao Meng, and Yukang Chang. 2022. "Research on Six-Wheel Distributed Unmanned Vehicle Path Tracking Strategy Based on Hierarchical Control" Biomimetics 7, no. 4: 238. https://doi.org/10.3390/biomimetics7040238

Article Metrics

Back to TopTop