Next Article in Journal
A Survey of Autonomous Driving Trajectory Prediction: Methodologies, Challenges, and Future Prospects
Previous Article in Journal
Coordinated Motion Pattern of Dual Forging Manipulators Based on Forging Deformation Behavior and Press Kinematics
Previous Article in Special Issue
Collision Avoidance of Driving Robotic Vehicles Based on Model Predictive Control with Improved APF
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Slip-Based Model Predictive Control Approach for Trajectory Following of Unmanned Tracked Vehicles

by
Ismail Gocer
1,* and
Selahattin Caglar Baslamisli
2
1
Graduate School of Science and Engineering, Hacettepe University, Beytepe, 06800 Ankara, Türkiye
2
Department of Mechanical Engineering, Hacettepe University, Beytepe, 06800 Ankara, Türkiye
*
Author to whom correspondence should be addressed.
Machines 2025, 13(9), 817; https://doi.org/10.3390/machines13090817
Submission received: 25 June 2025 / Revised: 21 August 2025 / Accepted: 22 August 2025 / Published: 5 September 2025

Abstract

In the field of tracked vehicle dynamics, studies show that vertical loads are concentrated under road wheels on firm road conditions, allowing slip-based models of tracked vehicles to be designed similar to wheeled vehicle models. This paper proposes a slip-based nonlinear two-track prediction model for model predictive control (MPC), where track forces under road wheels are calculated with a simplification procedure implemented onto shear displacement theory. The study includes a comparative analysis with a kinematic prediction model, examining scenarios such as constant speed cornering and spiral maneuvers. Validation is carried out by comparing the simulation results of the proposed controller with field test data acquired from a five-wheeled tracked vehicle platform, including measurements on asphalt and stabilized road conditions. The results demonstrate that the slip-based model excels in trajectory tracking, with lateral deviations consistently below 0.25 m and typically around 0.02–0.08 m RMS depending on the scenario. By improving the computational efficiency and ensuring precise navigation, this approach offers an advanced control solution for tracked vehicles on firm terrain.

1. Introduction

Motion control studies have gained significant attention, particularly in autonomous vehicles, including robotics and unmanned systems. Tracked vehicles are often characterized by their use of continuous tracks instead of wheels and are widely employed in scenarios involving rough or uneven terrains. However, this paper specifically focuses on the trajectory tracking problem under firm ground conditions, which is also crucial for achieving autonomy in unmanned tracked vehicles (Figure 1). While these vehicles are capable of handling diverse terrains, firm ground presents challenges such as managing high-slip conditions and ensuring accurate trajectory prediction. Our study aims to address these challenges by developing a robust predictive model tailored to firm ground scenarios, enhancing both stability and navigation precision. Various methods have been explored to address these issues, yet a robust predictive model is necessary to enhance navigation accuracy and stability. The trajectory tracking problem is commonly the basis for autonomy and it is handled with many different methods. These approaches can be categorized under following groups:
i.
Classical control methods such as PID control [1];
ii.
Kinematic methods such as pure pursuit and Stanley control [2,3,4];
iii.
Intelligent and learning based methods such as neural network-based control [5];
iv.
Optimization based methods such as model predictive control.
Figure 1. Illustration of an unmanned tracked vehicle platform [6].
Figure 1. Illustration of an unmanned tracked vehicle platform [6].
Machines 13 00817 g001
In tracked vehicle dynamics, methods such as classical PID control offer simplicity but often fail to manage the complex nonlinearities in dynamic systems. Kinematic approaches such as pure pursuit provide basic geometrical path tracking but struggle under conditions with significant slip. Intelligent control methods such as neural networks have potential for adaptability, yet their robustness is still questionable due to limitation with training dataset. Model predictive control (MPC) is effective for handling constraints but becomes computationally challenging when dealing with high-slip scenarios and due to detailed contact mechanics specific to tracked vehicles. These existing methods, while valuable, often do not fully address the challenges at higher speeds, underscoring the need for robust and computationally fast predictive models.
As an optimization-based approach, MPC provides a structured optimal control problem solving technique while conveniently handling the system constraints of linear or non-linear systems. For the trajectory following problem, the MPC approach is extensively used especially in wheeled vehicles. Prediction models for wheeled vehicles show variety, from kinematic single-track models to dynamic two-track models. In high-slip conditions, kinematic single-track models become insufficient for catching the dynamics of actual plant. Therefore, one-track or two-track dynamic models are used introducing the slip of the tires [7,8,9].
Dynamic modelling of tracked vehicles has been widely investigated in the literature, where ride and handling studies are generally covered separately. For ride dynamics, suspension dynamics, track–ground contact relationships, and track wrapping algorithms are mostly studied for both hard and soft soil terrain conditions [10,11,12,13]. In handling studies of these vehicles, accurate modelling constitutes a much more complex phenomenon compared to wheeled vehicles, due to slip occurring through the large contact areas of track pads during skid steer maneuver. Kinematic and dynamic approaches are used in the modelling of these vehicles. In kinematic models, the simplest method includes calculating the instantaneous center of velocity using the track velocities of the vehicle, with slip effects being disregarded [14] (Figure 2a). Additionally, a further improved method for kinematic model is the sliding model, where the instantaneous center is shifted forward due to sliding track characteristics [15,16] (Figure 2b).
In MPC-based trajectory following applications for tracked vehicles, kinematic models are most common due to their simplicity and low computational cost. Zhou et al. [14] employed a torque-driven linearized kinematic model neglecting slip, achieving acceptable results at low speeds with a lightweight test robot using only X, Y, and yaw as controlled states. An EKF-enhanced kinematic model in [17] estimated road and steering resistance, improving lateral tracking by 24% over the basic model in 10–20 km/h off-road tests. In [15], a sliding kinematic model based on the instantaneous turning center was applied to minimize heading deviations for large turning radii. The same authors [16] later updated slip parameters from measured states and applied MPC to the sliding model, outperforming pure pursuit, classical MPC without slip, and the Levenberg–Marquardt method.
When considering the load concentration of the tracks on firm ground, tracked vehicle models can be designed similarly to wheeled vehicle models for slippage calculations under road wheels. A good example for this approach is given in [18], where track force is represented by magic formula as in wheeled vehicles.
Apart from these studies, recent ones have explored diverse trajectory-tracking strategies to enhance the control and efficiency of unmanned vehicles. Reference [19] proposed a polytopic model-based robust MPC for autonomous wheeled vehicles, reducing complexity by using fewer Takagi–Sugeno vertices and adding an H∞ compensation controller for uncertainty and disturbance rejection, validated in Carsim/Simulink. In their extended study [20], they introduced an event-triggered system (ETS) to reduce the communication load while maintaining path-tracking accuracy, validated through hardware-in-the-loop tests. This illustrates the importance of computational efficiency in predictive controllers. Other studies include adaptive MPC for wheel–track hybrid vehicles to address nonlinear and coupled dynamics [21], quartic polynomial planning plus MPC for crawler pavers [22], energy-efficient off-road path planning using a modified A* algorithm [23], online learning and model updating via recursive least squares and Kalman filtering [24], and decoupled adaptive motion control for leader–follower tracked vehicles to maintain precise speed and curvature tracking [25]. These studies collectively highlight the innovative approaches in trajectory tracking, focusing on predictive control strategies to improve the performance and reliability of automated and unmanned vehicle systems across different environments and tasks.
Despite all these studies, there remains a gap in developing robust predictive models for tracked vehicles that can integrate adaptive capabilities and improve decision-making processes under varying environmental conditions. Additionally, most of the studies, especially involving robotic platforms, present low velocities limited to 20 km/h, and the performances of the prediction models are not commonly captured beyond these limits.
To address this gap, we propose a simplified slip-based prediction model for MPC that achieves a practical balance between accuracy and computational efficiency. Unlike purely kinematic methods, which lose accuracy under high-slip conditions, and full dynamic models, which are too computationally demanding for real-time use, the core novelty of this study lies in simplifying the exponential shear displacement formulation (Equation (29)). In the proposed method, the complex integral operation is replaced with an equivalent multiplication of resultant slip velocities and effective contact time [26]. A further analysis shows that particular group of parameters, including the exponential shear displacement function, become insensitive at higher track speeds and slip values. These terms are, therefore, substituted with a constant factor ( K s i m p ), which yields a mathematically simpler yet bounded error representation of slip dynamics. This innovation not only reduces the computational load but also makes the linearization of the nonlinear model at each MPC step more straightforward and less demanding in the calculation. Building on this principle, the study introduces a torque-driven, slip-based two-track vehicle model that computes slip velocities and contact forces under each wheel, enabling nonlinear MPC to be feasible for real-time trajectory tracking of tracked vehicles operating at higher speeds on firm terrain.
The controller is applied on a plant model, which is taken from [27], and which has extended features through the application of shear displacement theory and built upon the improvements of [28,29,30]. With mentioned modifications, the results of the proposed nonlinear prediction model are compared with the kinematic prediction model in [14], in different scenarios such as (i) cornering maneuvers with increasing speed and (ii) spiral maneuvers with constant speed. Furthermore, a reference trajectory of the created complex test track is used to investigate the performance of the proposed model.
The analyses are conducted in a simulation environment tailored for unmanned driving conditions; however, the controller’s accuracy is validated by replicating the test results from a series of controlled experiments carried out on a five-wheeled tracked vehicle platform, operated in manned mode. These experiments are designed to evaluate the controller’s performance in various scenarios, including low-speed cornering and high-speed maneuvers on an asphalt track, as well as stabilized test parkour. The verification studies involve data from GPS tracking and speed and torque measurements from the sprocket driving shafts, ensuring the controller’s effectiveness and reliability. The postprocessing of these measurements and all methodologies applied in this study is conducted in MATLAB—Simulink R2021b software environments.
The current article comprises eight subsections, including Section 1, which has provided an introduction for the study. In Section 2, the plant model is explained. In Section 3, details of the kinematic-based prediction model are explained. In Section 4, the fundamentals of the proposed nonlinear prediction model are introduced. Additionally, the main contribution of the article is explained here by emphasizing the conducted simplifications in the shear displacement model. In Section 5, the MPC formulation for trajectory tracking problem is described. Results of trajectory following studies are compared in Section 6 for the kinematic-based and proposed slip-based prediction model. In Section 7, the verification studies are discussed, where the collected test data are utilized. Both the vehicle’s measured states and the measurements from the sprocket driving shaft are employed to verify the controller’s output. Finally, the outcomes of the study are summarized in Section 8.

2. Tracked Vehicle Plant Model

The plant model for this study is taken from [27]. The model provides improvements for the transient calculation methods onto past contributions to skid steering tracked vehicle applications. The plant model includes the following features:
(i) Concentrated vertical load under road wheels;
(ii) Discretized cells for track pads under road wheels;
(iii) Shear displacement-based force development;
(iv) Vertical load changes due to longitudinal, lateral acceleration, track pretension, and applied sprocket torques.
In the model, track pads are discretized to smaller portions and kinematic calculations are performed for each portion (Figure 3b). First, longitudinal, lateral, and resultant slip velocities of each discretized cells are calculated with Equations (1)–(3), where V s x k m i j , V s y k m i j , and V s k m i j are the longitudinal, lateral, and resultant slip velocities, respectively; x w i j and y w i j represent the position of each wheel center in vehicle coordinates; x p k m i j and y p k m i j are the positions of the discretized cells in wheel center coordinates; V t j is the velocity of each track.
V s x k m i j = V x y w i j ω y p k m i j ω V t j ,
V s y k m i j = V y + x w i j ω + x p k m i j ω ,
V s k m i j = V s x k m i j 2 + V s y k m i j 2 .
By integrating the slip velocity along the contact timing of track pads, the slip displacement of each cell can be calculated for both longitudinal and lateral directions. The combination of these displacements gives the overall shear displacement of the cells, as shown in Equation (4), where j k m i j corresponds to resultant shear displacement. The integration time bound t k m i j represents the contact duration of each cell with the ground, which changes with respect to the velocity of the track. Applying the equation used in [31], the shear stress of each track pad cell is calculated in Equation (5), where F z i j is the vertical load on each wheel, A is the track pad area, μ is the friction coefficient, and K is the shear deformation modulus.
j k m i j = t t k m i j t V s k m i j   d t ,
τ k m i j = F z i j A μ ( 1 e j k m i j / K ) .
Components of shear forces are summed for each track pad cell in order to calculate total forces under each road wheel in longitudinal ( Q x i j ) and lateral ( Q y i j ) directions. Additionally, moments created by longitudinal and lateral forces ( M x i j , M y i j respectively) are calculated. Finally, equations of motion are calculated in Equations (6)–(8), where a x is longitudinal acceleration; a y is lateral acceleration; R 1 and R 2 are rolling resistance forces of the right and left tracks, respectively; L 1 and L 2 are the lateral distances of the tracks to the CG of the right and left tracks, respectively.
m a x = j = 1 n i = 1 2 Q x i j + R 1 + R 2 ,
m a y = j = 1 n i = 1 2 Q y i j ,
I z z ω ˙ = j = 1 n i = 1 2 M x i j + M y i j + R 1 L 1 R 2 L 2 .
To demonstrate the fidelity of the plant model, sprocket torque results for various turning radii and speeds are compared against the well-known general theory for skid steering presented by Wong et al. [31] and test data in [32,33] obtained from a 25.5 ton tracked vehicle. The comparison, presented in Figure 4, with its numerical data provided in Appendix A, shows that the plant model produces results closely matching the test data, particularly at speeds below 21.3 km/h, with deviations increasing at higher speeds. Nevertheless, the model successfully captures the overall trends and serves as a strong example of a transient tracked vehicle modeling approach that applies state-of-the-art contact force calculations based on the shear displacement method. It should be noted that the general theory results are presented here using the “concentrated load under each road wheel” assumption, one of the approaches investigated by Wong, which is likewise adopted in the plant model.
Building upon the plant model outlined in this section, which covers the essential dynamics of the tracked vehicle, we now advance to the development of predictive models crucial for trajectory tracking. In Section 3, we introduce the kinematic prediction model, offering a simplified approach to forecasting vehicle motion based on geometric and velocity parameters. Subsequently, Section 4 describes the slip-based prediction model, which incorporates the effects of wheel–terrain interactions to enhance predictive accuracy. These models serve as foundational components within the model predictive control framework, which is further explained in Section 5.

3. Kinematic-Based Model as a Foundation for MPC Prediction

In this section, we introduce a kinematic vehicle model as outlined in [14]. This model is used to assess its performance in comparison to the slip-based model described in Section 4. Both models operate as nonlinear prediction tools within the model predictive control framework, enabling predictions of vehicle motion to facilitate the trajectory following control of the plant model described in Section 2. The integration of these models within the MPC formulation is further detailed in Section 5.
The layout of the model is presented in Figure 2a. The positions in longitudinal and lateral coordinates ( x c ,   y c ) and the yaw angle ( ψ ) of the vehicle are the main states of the model, where the velocities of the outer and inner tracks ( v o ,   v i ) are the main inputs of the system initially. Nonlinear equations for vehicle motion can be written with the following nonholonomic form, where T refers to the thread of the vehicle.
x c ˙ y c ˙ ψ ˙ = 0.5 cos ψ 0.5 cos ψ 0.5 sin ψ 0.5 sin ψ 1 / T 1 / T v o v i .
To extend the given definition and apply the sprocket torques as inputs of the system, tracked vehicle force equations and kinematic relationships can be used. Dynamics at the sprocket level can be defined as in Equation (10), where, F o i defines the required traction force (Equation (11)), which comprises resistance due to (i) longitudinal motion F R e s , and (ii) the so-called turning resistance moment— M S t e e r , while the rest of the components belong to (iii) translational and (iv) rotational inertial forces ( δ m v e h · v C ˙ 2 and I z z · ψ ¨ T , respectively).
J · ω ˙ s p r o i = τ s p r o i F o i · r s p r .
F o i = F R e s o i + δ m v e h · v c ˙ 2 ± M S t e e r + I z z · ψ ¨ T .
The turning resistance moment ( M S t e e r ) [31], steering resistance force ( F S t e e r ), and effective lateral friction coefficient ( μ t ) [34] definitions are given in Equations (12) and (13).
F S t e e r = M S t e e r T = μ t · m · g · L 4 · T ,
μ t = μ m a x · 0.925 + 0.15 · R T 1 .
Combining Equations (10) and (11), sprocket level equations take the following form:
J · ω ˙ s p r o i = τ s p r o i F R e s o i 2 + δ m v e h · V c ˙ 2 ± I z z · ψ ¨ T ± F S t e e r · r s p r .
Combined kinematic equations of motion of the tracked vehicle are obtained as in Equations (15)–(19):
x ˙ = A x + B u ,
x = x c y c ψ ω s p r o ω s p r i v c ,
A = 0 0 0 0 0 0 0 0 0 0 0 0 r 2 c o s ( ψ ) r 2 c o s ( ψ ) 0 0 0 0 r 2 s i n ( ψ ) r 2 s i n ( ψ ) 0 0 0 0 r T r T 0 0 0 0 r 2 r 2 0 0 0 0 ,
B = r s p r · k 1 r s p r k 1 k 1 k 2 r s p r k 2 k 2 k 2 r s p r k 2 k 2 k 1 r s p r k 1 k 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 ,
u = τ s p r o F R e s o F S t e e r R e s o τ s p r i F R e s i F S t e e r R e s i ,
where k 1 and k 2 in Equations (17) and (18) comprise terms related to inertial effects, such as the inertia of driveline J and yaw inertia of the vehicle J c , as shown in Equations (20) and (21).
k 1 = 1 2 1 J + δ m v e h · r s p r 2 + 1 J + 2 · J c · r s p r 2 T 2 ,
k 2 = 1 2 1 J + δ m v e h · r s p r 2 1 J + 2 · J c · r s p r 2 T 2 .
In concluding the vehicle model introduced in this section, this approach provides a foundational basis for the vehicle motion obtained by applying the kinematic laws. To facilitate its application within the MPC framework, we linearize the nonlinear state matrices by their Jacobians. This linearization process yields discretized state representations, essential for predicting future states over the defined prediction horizon. These specific procedures will be explained thoroughly in Section 5.

4. Development of a Simplified Slip-Based Model as a Foundation for MPC Prediction

This section introduces the core research contribution of this study—a simplified slip-based nonlinear prediction model specifically designed for model predictive control of tracked vehicles. Traditional shear displacement models often involve computationally intensive integrals, making them less practical for real-time applications. The proposed model addresses this challenge by implementing further simplifications, enhancing computational efficiency while maintaining effective tracking performance. The simplified model is verified later through a comparison with the full nonlinear shear-displacement-based plant model. As a remainder, this section, as well as Section 3, establish the fundamentals of the prediction models. Next, these models are utilized in the MPC framework as the derivations that will be explained in Section 5.
Differing from kinematic models, the proposed model includes the contact force generation characteristics of track pads. Assuming that the vertical load under track pads is concentrated under road wheels, calculations can be performed based on point contact force generation as in wheeled vehicle applications. Therefore, slip velocities are calculated for each road wheel location with kinematic relations. Shear forces developed by the pads are estimated for longitudinal and lateral directions. Finally, equations of motion based on these forces are constructed.
As described in Equations (4) and (5), calculating shear forces in tracked vehicles typically involves integrating the slip velocity over the contact time, a process that can be computationally intensive and challenging to linearize. To address this, our study applies simplifications in track force estimation to develop a more efficient prediction model. As stated in [28], shear displacement can be approximated with the multiplication of combined slip and average contact times, as in Equation (22), where j i j defines the shear displacement under each road wheel, V S i j defines the resultant slip velocity, and t a v g is the average contact time under road wheels. Notice that this equation is a simplified version, where t a v g i j is calculated by dividing the contact length ( L c o n i ) under road wheels by the track velocity, as in Equation (23). Here, l i is the vectoral distance of the ith road wheel to the CG. Therefore,   L c o n i defines the distance of the road wheel to first road wheel.
j i j = V S i j · t a v g i j ,
t a v g i j = L c o n i V t j = l 1 l i V t j .
The slip ratio under each wheel can be expressed with Equations (24)–(26).
s x i j = V s x i j r s p r · ω s p r j ,
s y i j = V s y i j r s p r · ω s p r j ,
s i j = V s x i j 2 + V s y i j 2 r s p r · ω s p r = V s i j r s p r · ω s p r j .
Utilizing Equations (24)–(26), components of the forces in longitudinal and lateral directions can be defined as in Equations (27) and (28), where F i j is the resultant force (Equation (29)), which refers to the well-known shear displacement approach [31].
F x i j = F i j · s x i j s i j = F i j · V s x i j V s i j ,
F y i j = F i j · s y i j s i j = F i j · V s y i j V s i j ,
F i j = F z i j · μ · 1 e j i j K .
The last term in Equation (29) is the exponential function, and by combining Equations (22) and (23), the following definition is obtained:
f e x p i j = 1 e j i j K = 1 e V s i j / V t j K / L c o n t a c t i .
Combining Equations (27)–(30), the force equations become Equations (31) and (32).
F x i j = V s x i j · F z i j · μ · f e x p i j V s i j ,
F y i j = V s y i j · F z i j · μ · f e x p i j V s i j .
Analyzing the effect of change of V s i j and the V t j in change of f e x p / V s , the surface in Figure 5 is obtained for the mid road wheel. The increases in V s i j and V t j parameters lead f e x p / V s to operate on an almost planar surface and become insensitive to their increase. This feature can be used in the simplification of the prediction model. Instead of an exact calculation of this factor, a constant value can be applied, so that the calculation effort in track forces decreases. Therefore, calculations of longitudinal and lateral forces can be approximated with Equations (33) and (34). Finally, the layout of the proposed model can be constructed as in Figure 6. The method used to calculate the vertical load under each wheel is explained in Appendix B.
F x i j V s x i j · F z i j · μ · K s i m p ,
F y i j V s y i j · F z i j · μ · K s i m p .
The longitudinal slip velocities under the ith road wheel on the right side and left sides of the vehicle are calculated using Equations (35) and (36).
V s x i R = v x + T 2 · ψ ˙ ω s p r R · r s p r ,
V s x i L = v x T 2 · ψ ˙ ω s p r L · r s p r .
Moments created by longitudinal forces on the right and left sides are then calculated according to Equations (37) and (38), where F x i R and F x i L are the transmitted longitudinal forces under the ith wheel on the right and left sides, respectively.
M x i R = T 2 · i = 1 5 F x i R ,
M x i L = T 2 · i = 1 5 F x i L .
The lateral slip velocities under the ith road wheel on the right side and left side of the vehicle are calculated using Equation (39).
V s y i R = V s y i L = v y + l i · ψ ˙ .
Moments created by lateral forces on the right and left sides are then calculated according to Equations (40) and (41), where F y i R and F y i L are transmitted lateral forces under the ith wheel on the right and left sides, respectively.
M y i R = i = 1 5 F y i R · l i ,
M y i L = i = 1 5 F y i L · l i .
Using the force and moment calculations, state calculations for the longitudinal and lateral velocities of the vehicle in body coordinates and yaw velocity are conducted with Equations (42)–(44).
v ˙ x = i = 1 5 j = 1 2 F x i j F R e s m + v y · ψ ˙ ,
v ˙ y = i = 1 5 j = 1 2 F y i j m v x · ψ ˙ ,
ψ ¨ = M x i R + M x i L + M y i R + M y i L I z z .
Velocities of the vehicle in global coordinates are calculated by applying appropriate transformations, as shown in Equations (45)–(47). The integration of these parameters over time provides the calculation of position states ( x , y and ψ ) given in Equation (51).
V x = v x · cos ψ v y · sin ψ ,
V y = v x · sin ψ + v y · cos ψ ,
ψ ˙ = ω .
Finally, states for sprocket speeds are calculated by differential equations given in Equations (48) and (49).
ω ˙ s p r R = τ s p r R i = 1 5 F x i R · r s p r J ,
ω ˙ s p r L = τ s p r L i = 1 5 F x i L · r s p r J .
The states and inputs of the nonlinear model are summarized in Equations (50)–(52).
x ˙ = V x V y ψ ˙ v ˙ x v ˙ y ψ ¨ ω ˙ s p r R ω ˙ s p r L ,
x = x y ψ v x v y ψ ˙ ω s p r R ω s p r L ,
u = τ s p r R τ s p r L F R e s R F R e s L .
In the MPC structure, τ s p r o and τ s p r i are designed as manipulated variables, whereas resistance forces are fed to the system as calculated inputs. The reference trajectory is fed to the system in terms of its longitudinal and lateral positions and yaw angle, as in the kinematic-based prediction model: x r e f = [ X r e f Y r e f ψ r e f ] .
In this section, we develop a simplified slip-based model. This model incorporates slip dynamics, addressing the limitations of the kinematic model. The next section provides a procedure for how these models are utilized to predict future vehicle states, formulate control objectives, and implement constraints to achieve optimal trajectory tracking performance.

5. MPC Problem Formulation

In this section, we detail the model predictive control (MPC) formulation, utilizing both the kinematic model from Section 3 and the slip-based model from Section 4 as prediction models for trajectory tracking. The nonlinear prediction models used in this study (kinematic and slip-based) are linearized at each controller sampling instant (Ts = 0.05 s) about the current measured states and latest control inputs. This yields the updated Jacobian matrices A J and B J of the system dynamics with respect to states and inputs in Equations (62)–(65). These continuous-time Jacobians are then discretized using the Euler method (Equations (66)–(68)) to produce the local linear prediction model in discrete-time state–space form. Based on this model, the MPC cost function is formulated to penalize deviations from the reference trajectory and excessive control changes over a prediction horizon N = 20 (1 s look-ahead) and a control horizon M = 2 (0.1 s control window). The resulting QP problem is solved using MATLAB’s fmincon function; only the first control action of the optimized sequence is applied to the plant before the horizon is shifted forward and the procedure repeated. An analysis for computational efficiency is introduced later in Section 6.2, with a sensitivity analysis of these specific MPC parameters providing the timing headroom for the calculation of each step-in solution of the MPC problem over a specific scenario. To facilitate the MPC design, Figure 7 presents a flowchart of this process, showing the mentioned process sequence.
To start with the derivation, generalized discrete state space calculations can be given with the following equations, where k is the stage number of the problem:
x k + 1 = A x ( k ) + B u ( k ) ,
y k = C x ( k ) + D u ( k ) .
States for the vehicle, which follow the trajectory perfectly, are calculated by the function given in Equation (55). The inputs of this function are the reference state vector (Equation (56)) and the reference manipulated vector u r e f (Equation (57)).
x ˙ r e f = f x r e f , u r e f .
x r e f = X r e f Y r e f ψ r e f ,
u r e f = τ S p r R τ S p r L ,
Actual states of the vehicle are calculated by Equation (58).
x ˙ = f x , u = A x + B u .
Nonlinear state equations are linearized with Taylor series expansion, as in Equation (59).
x ˙ r e f f x r e f , u r e f + d f d x | x x r e f + d f d u | u u r e f .
Subtracting Equations (58) and (59), Equations (60) and (61) can be obtained. A J and B J are Jacobian matrices with respect to ( x x r e f ) and ( u u r e f ) , respectively (Equations (62) and (63)).
x ~ ˙ = x ˙ x ˙ r e f f x , u f x r e f , u r e f d f d x x x r e f d f d u u u r e f ,
x ~ ˙ = A J x ~ + B J u ~ ,
A J ( t ) = d f d x | x x r e f ,
B J ( t ) = d f d u | u u r e f .
Using the state matrices in Equations (17) and (18), Jacobian matrices of the kinematic-based nonlinear model (Section 3) are computed by taking the partial derivatives of the system dynamics with respect to the state vector x in Equation (16) and the input vector u in Equation (19). The same linearization procedure is applied to the slip-based prediction model, where the Jacobians are computed from the nonlinear state Equations (42)–(49) with respect to states given in Equation (51) and the input vector in Equation (52). The resulting continuous-time Jacobians A J and B J define the local linear approximation of the nonlinear dynamics at a given operating point. Based on these calculations, the explicit form of A J is given in Equation (64), while B J is expressed in Equation (65) for the slip-based prediction model. The detailed, term-by-term partial derivatives used to construct these matrices are provided in Appendix C, enabling direct traceability from the nonlinear state equations to the elements of A J and B J .
A J = 0 0 v y cos ψ v x sin ψ cos ψ sin ψ 0 0 v x cos ψ v y sin ψ sin ψ cos ψ 0 0 0 0 0 0 0 0 F r e s + F z s u m K s i m p m ψ ˙ 0 0 0 ψ ˙ K s i m p F z s u m m 0 0 0 K s i m p T F z L s u m F z R s u m 2 · I z z K s i m p i = 1 5 F z i R l i + F z i L l i I z z 0 0 0 K s i m p r s p r F z R s u m J 0 0 0 0 K s i m p r s p r F z L s u m J 0 0 0 0 0 0 0 1 0 0 2 m v y + K s i m p T F z L s u m F z R s u m 2 m K s i m p r s p r F z R s u m m K s i m p r s p r F z L s u m m m v x + K s i m p i = 1 5 F z i R l i + F z i L l i m 0 0 K s i m p T 2 F z s u m + 4 i = 1 5 F z i R l i 2 + F z i L l i 2   4 · I z z K s i m p T r s p r F z R s u m 2 I z z K s i m p T r s p r F z L s u m 2 I z z K s i m p T r s p r F z R s u m 2 J K s i m p r s p r 2   F z R s u m J 0 K s i m p T r s p r F z L s u m 2 J 0 K s i m p r s p r 2   F z L s u m J ,
B J = 0 0 0 0 0 0 1 J 0 0 0 0 0 0 0 0 1 J ,
where F z L s u m ,   F z R s u m , and F z s u m represent the sum of vertical loads on the left side, right side, and both sides, respectively; F z i R ,   F z i L are vertical loads for the ith road wheels of the right and left sides, respectively. Next, discretized forms of the linearized new state equations are then obtained with Equations (66)–(68).
x ~ k + 1 = A d k x ~ k + B d k u ~ k ,
A d k = I + A J k · T s ,
B d k = B J k · T s .
Prediction states for the horizon length of N and control horizon M are calculated as Equations (69)–(73).
X k + 1 + i k = A k · X k + i | k + B k · U k | k ,
X k + 1 + i k = x k + 1 k x k + N k ,
U k k = u k k u k + M 1 k ,
A k = A d A d 2 A d N 1 A d N ,
B k = B d 0 0 A d B d B d 0 A d 2 B d A d B d B d 0 0 0 0 0 0 A d N 1 B d A d N 2 B d 0 0 0 B d .
Finally, the output of the linearized equations is found with appropriate output matrices as in Equation (74). Here, D k is zero, since the output function recalls only [x, y,   ψ ] outputs, which are independent from the inputs.
y k + 1 + i k = C k · X k + i | k + D k · U k | k ,
where   C k = C 0 0 0 0 C 0 0 0 0 0 0 0 0 C 0 0 0 0 C ,
and   C = 1 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 1 0 0 0 0 0 .
A generic MPC formulation is given in Equation (77), where y is the output, y r e f is the reference signal, and u is the control input; Q and R are the weights between the output error and the control variables.
m i n u 0 , u 1 u N 1 J = min u 0 , u 1 _ u N 1 i = 1 N 1 Q y k + 1 + i k y r e f k + 1 + i 2 + R U k + i + 1 2 .
The quadratic problem of MPC can be defined with Equations (78)–(80), where H is the Hessian matrix and F is the linear component of the objective function problem.
J = 1 2 U T H U + F T U ,
H = 2 B T Q B + R ,
F = 2 B   T Q A x ~ .
The constraints for input sprocket torques following conditions in Equations (81) and (82) are then applied, where τ m a x and τ m i n are the maximum and minimum sprocket torques, respectively.
τ m i n < τ o i < τ m a x ,
τ m a x = τ m i n = m · g 2 · μ m a x · r s p r .
Change of input torques are limited with the following constraints:
τ ˙ m i n < τ ˙ o i < τ ˙ m a x ,
τ ˙ m a x = τ ˙ m i n = 7500 N m s e c .
Therefore, the MPC problem is solved subject to the inequalities:
F U · U k g U ,
F U d o t · U ˙ k g U d o t ,
Here:
F U = 1 0 0 1 1 0 0 1   ,     g U = τ m a x τ m a x ,
F U d o t = 1 0 0 1 1 0 0 1 ,   g U d o t = τ ˙ m a x τ ˙ m a x .
The objective of the problem is to find the optimized control sequence and apply the first control value to the system u * ( 1 ) . Repeating this sequence until the end of the calculation finalizes the MPC procedure.
U * = a r g m i n J .

6. Simulation Results and Performance Assessment of the Proposed Controller

In this section, the study results are obtained by implementing the controller rules within a simulation environment on an unmanned five-wheeled tracked vehicle, using the dataset and MPC parameters specified in Table 1. It is important to note that these vehicle-specific parameters also correspond to the specifications of the vehicle used in the field tests discussed in Section 7. Parameters such as the friction coefficient (μ) and shear modulus ( K ) refer to the study in [31], where derivations for track forces are analyzed for firm ground such as asphalt, as is the case in this study. A sensitivity analysis for the friction coefficient and MPC parameters (prediction and control horizon) is introduced in Section 6.2.

6.1. Performance Evaluation of Kinematic- and Slip-Based Controllers

In this section, the performance of the slip-based model prediction model is compared against the kinematic-based model with the following scenarios:
  • SCENARIO 1: Cornering with a 40 m turning radius, while the speed increases up to 50 km/h;
  • SCENARIO 2: Steady cornering with 10 km/h velocity on a spiral.
  • A further scenario is conducted for the slip-based model to emphasize its advantages and better performance:
  • SCENARIO 3: Trajectory tracking on a fictitious complex track at high speeds.
The selected simulation scenarios are designed to evaluate the trajectory tracking performance of the proposed controller under diverse and progressively challenging conditions. Scenario 1, inspired by the ISO 4138 automotive standard [35] for steady-state circular driving, assesses the vehicle's behavior under increasing lateral acceleration at rising speeds, effectively demonstrating the controller’s stability and precision during high-load cornering. Scenario 2 investigates low-speed handling in a progressively tightening spiral path, serving to evaluate precision at low velocities and moderate slip conditions. Finally, Scenario 3 examines controller performance over an extended trajectory with varying curvatures and higher speeds, representing a more realistic driving profile that combines transient and steady-state behaviors. Collectively, these scenarios offer a comprehensive assessment of the controller’s robustness, accuracy, and adaptability across different operational regimes.
  • SCENARIO 1: R40 INCREASING SPEED
In this scenario, the vehicle drives on a R40 circle while the reference speed increases. Meanwhile, the lateral acceleration increases up to 0.5 g. This scenario is used as the benchmark for the slip-based model, where the simplification factor of K S i m p (Equations (33) and (34)) is altered. Lateral deviation and yaw angle RMS errors with respect to the change of this factor are listed in Table 2. Based on these results, K S i m p = 1.5 was selected for further scenarios, since it yields the smallest lateral deviation (0.015 m RMS). Across the tested interval K S i m p = 0.5–1.5, the RMS lateral deviation remains within the bounded range of 0.015–0.181 m, and the RMS yaw error remains within 0.026–0.029 rad. This quantifies the bounded approximation error introduced by the constant value simplification. Moreover, for K S i m p values below 2.0, the lateral deviation error decreases, supporting the conclusion from Figure 5 that the sensitivity of f e x p / V s decreases with increasing speed.
In Figure 8, the results of the slip-based model are compared with the kinematic model. The kinematic-based model departs from the road at about 8.7 s (>0.5 m of lateral deviation), whereas the highest lateral deviation for the slip-based model is not higher than 0.03 m during the whole simulation (Figure 8b). At this point, the kinematic-based model reaches at most 0.17 g of lateral acceleration before 0.5 m of departure, while the slip-based model reaches up to 0.51 g of lateral acceleration at the end of the simulation.
  • SCENARIO 2: 10 KMH SPIRAL
In the second scenario, the vehicle moves around a spiral trajectory with 10 km/h steady velocity, while the turning radius decreases. The slip-based vehicle is able keep the lateral deviation under 0.1 m, whereas the error of the kinematic-based model increases up to about 0.35 m (Figure 9c). Additionally, the error for the yaw angle of the vehicle reaches up to about 5 degrees for the kinematic-based model, while the slip-based model error is at most about 3.9 degrees. The lateral acceleration values reach to 0.23 g in the kinematic-based prediction model due to higher longitudinal velocity error, whereas 0.20 g is achieved in the slip-based prediction model.
In Table 3, RMS errors for control metrics are presented, for the simulations with kinematic based prediction model and slip-based prediction model. It is obvious from the table that results of slip-based model are superior compared to results of kinematic prediction model. In the R40 case with increasing speed, the kinematic model produces significant lateral deviation errors due to departure of the vehicle from the track. Additionally, results from an extra scenario, where the vehicle negotiates an R20 corner at a steady 20 km/h, are also provided.
  • SCENARIO 3: DRIVE ON A FICTITOUS COMPLEX TRACK WITH HIGH SPEED
In the final scenario, free driving on a prepared complex track is analyzed (Figure 10). The reference speed profile (Figure 11b) is created up to the 50 km/h boundary. The velocity profile is limited with longitudinal and lateral acceleration of 0.5 g. According to the results, the slip based prediction model is able to control the plant well, with zoomed sections presented in Figure 12. In the results, the maximum lateral deviation is not more than 0.25 m (Figure 11a). The vehicle is also able to track the desired velocity profile with certain minimal overshoot and undershoot errors (Figure 11b). In Figure 13 outputs of the controller are presented. It can be observed from the results that the controller produces identical torque values for straight motion regions (0–8 s and 35–45 s) and for the rest of the torque values, which are distinguished with respect to the outer and inner sides of the corners. The RMS values of the lateral deviation, yaw error, and lateral velocity error values are calculated as 0.080 m, 0.057 rad, and, 0.685 m/s, respectively.

6.2. Parameter Sensitivity Analyses

In this section, the results of the parameter sensitivity analyses are presented. These analyses show the capabilities of the proposed controller, as well as the its limitations. Two different analyses are presented: (1) effect of change of friction coefficient; (2) effect of change of MPC parameters.
In first analysis, an extended version of Scenario 1 is conducted for different friction coefficient values to evaluate the controller’s capability. In this scenario, the controller maintains the trajectory of the vehicle while the reference speed is increased with 0.1 g per one second. In Figure 14a, the trajectories of each vehicle driving on the road with different friction coefficients are presented. In Figure 14b, the reference velocity profile and actual velocity profiles of these vehicle are presented. At the brake points of each maneuver, lateral acceleration values are noted. In Table 4, the ratio of the reached lateral acceleration to the theoretical acceleration limit is presented. It can be concluded that the controller is more capable when the friction coefficient is high; however, its control limits become narrower when the friction coefficient decreases. Below the friction coefficient 0.2, the vehicle is not able to maintain the scenario. These conditions can be interpreted as the stability limit of the plant model, as well as the achievable limits of the controller.
In second analysis, changes of three crucial parameters of controller performance are analyzed: the prediction horizon (N), the control horizon (M), and the sampling time (Ts). Proper tuning of these parameters is essential to balance performance accuracy with the computational load. The results for Scenario 1, where the velocity increases on the same turning radius, are presented in Table 5. Increasing the prediction horizon N improves predictions of future behavior but also introduces additional complexity, which can increase RMS errors in certain states; for example, the yaw and longitudinal velocity errors increased when N was raised from 10 to 20. Conversely, the lateral deviation decreased over the same change of horizon. Extending the control horizon M provides the controller with more flexibility in future control actions and reduces errors, particularly in yaw and longitudinal velocity. This improvement can be observed when N = 20, as M is increased from 1 to 2. Overall, these results show that controller performance strongly depends on parameter tuning. The combination N = 20, M = 2 provides a balanced compromise between accuracy and efficiency; thus, it was used throughout this study.
Although these simulations were not deployed directly on hardware, the calculation efficiency of the controller was measured with the CPU execution time with MATLAB and compared with the defined sampling time of the controller-Ts. These calculations were carried out on a computer, with following specifications: Intel(R) Xeon(R) W-2295 CPU @ 3.00 GHz (Intel Corporation, Santa Clara, CA, USA), 64 GB DDR4 (Samsung, Suwon, Republic of Korea). In Table 5, tavg_step represents the average CPU calculation time for one step for the MPC algorithm to handle the calculations. The tavg_step values are compared with the sampling time in order to measure the headroom for the computation. The results show that although this computation can be handled with the given computer, real-time conditions and hardware with more limited capabilities might not sustain the operation for the configuration of N = 20 and M = 2, where the computation burden reaches ~80%. Therefore, decreasing the sampling time and prediction horizon can help in reducing the calculation burden, as can be seen in the last column of the table. This trade-off is typical for optimization-based control algorithms when considering their implementation on actual hardware.

6.3. Accuracy Analysis of the Simplified Model

In this section, the accuracy of simplified model against the plant model and its computational efficiency are analyzed. In the accuracy analysis, Scenario 1 is applied in order to scan the lateral acceleration span, while velocity is increasing on a constant turning radius. The same torque values in Figure 15 are provided to both models and the state outputs of the models are compared. According to the results of the comparison analysis, both models follow similar trajectories, as shown in Figure 16. However, the prediction model drives on a sharper curve than the plant model. By investigating the other states of the modes, such as the velocity, yaw rate, and sprocket speed, Figure 17 presents similar trends in these states. It should be emphasized here that when the prediction model is utilized in the MPC framework, the controller uses the states of the plant as the close-loop feedback, hence output torque values are regulated accordingly. Therefore, rather than obtaining perfect matching results with the prediction model, it becomes adequate that it provides similar trends with the plant model. Therefore, it works well with the presented scenarios.

7. Test Verification for the Controller Performance

This section includes a verification of the plant model used in the study and the proposed MPC controller. Since the plant model is driven by the torque outputs of the MPC, test scenarios are focused on measurements of the vehicle trajectory and the sprocket states. Therefore, the vehicle was instrumented with different measurement devices during the tests, such as with GPS (Racelogic VBOX IISX, VBOX Automotive, Buckingham, UK), IMU (SBG Ellipse-D, SBG Systems, Carrières-sur-Seine, France), Kvaser (Kvaser AB, Mölndal, Sweden), and encoder instruments for speed measurements of the sprocket driving shafts and a strain gauge-type measurement setup for torque measurements on the sprocket driving shafts. In Figure 18 the instrumentation package for measurements on the sprocket driving shaft is presented. The asphalt test track used in the conducted experiments is demonstrated in Figure 19.
Tests were conducted in three categories: (1) low-speed cornering maneuvers on the asphalt test track; (2) touring on the asphalt with higher speeds on the test track; (3) touring on a stabilized test parkour. The main aim of these tests was to observe the performance of the vehicle at low and high speeds and use the results for a comparison with the MPC controller outputs. The obtained GPS data from the tests were converted to Cartesian coordinates and fed to the MPC controller in the simulation environment as the reference trajectory to reproduce the results of the tests.
In the first scenario, the vehicle moves to its parking base at about 15 km/h of steady velocity. The GPS coordinates and results of the controlled plant model are presented in Figure 20, showing the close alignment of the test coordinates with the simulation outputs. Figure 21 verifies this fact by showing that the RMS error for the lateral deviation is 0.022 m.
Figure 22 presents the comparison of the test data and the reproduced test in terms of the velocity profile, speed, and torques at the sprocket. The RMS differences between the reproduced simulation data and the test data for velocity, sprocket speeds, and torques are as follows: 0.3 km/h, 5.3 rpm for the right sprocket, 5.1 rpm for the left sprocket, 0.11 normalized torque for the right sprocket, and 0.12 normalized torque for the left sprocket. Normalization is conducted with respect to the absolute maximum torque value of the test data and the RMS errors correspond to 11% and 12% of this value, which are within the acceptable range, while the torque signals of the simulation results show similar trends to the measurements.
In the second scenario, the vehicle tours around the track with steady velocity of about 40 km/h. In Figure 23, the trajectories of the GPS data and reproduced test data with the MPC controller are presented. Figure 23a provides a top-down view, whereas Figure 23b illustrates the trajectory in the time domain as the third dimension, showing close alignment of test coordinates with the simulation outputs. Figure 24 verifies this fact by presenting the RMS error for the lateral deviation, which is 0.025 m.
Figure 25 presents the comparison of the test data and the reproduced test in terms of velocity profiles, speeds, and torques at the sprocket. The RMS differences between reproduced simulation data and the test data for velocities, sprocket speeds, and torques are as follows: 0.4 km/h, 8.7 rpm for the right sprocket, 9.7 rpm for the left sprocket, 0.11 normalized torque for the right sprocket, and 0.18 normalized torque for the left sprocket. Normalization is conducted with respect to the absolute maximum torque value of the test data, and the RMS errors correspond to 11% and 18% of this value for the right and left sides, respectively. As a result, in both Test Scenario 1 and Test Scenario 2, the replicated simulation results show good alignment with the test results. The relatively high error in the left sprocket (inner side at corners) points out the necessity for improvement, especially at higher velocities, in future work.
Apart from the tests performed on the asphalt track, GPS data obtained from experiments conducted on a stabilized dirt road surface were also used to replicate these scenarios within the simulation environment, following the same procedure as for the asphalt track tests. These stabilized road experiments were carried out at a different time from the asphalt track trials; therefore, torque measurement sensors on the sprocket driving shafts were not available during these runs. Differing from the asphalt road, friction coefficient was applied as 0.7 to represent the loose surface of the test parkour. The mentioned parkour used in these experiments is demonstrated in Figure 26. The results of replicated simulations are presented in Figure 27 and Figure 28.
According to the results, the RMS differences between reproduced simulation data and the test data for velocities and sprocket speeds are as follows: 0.9 km/h, 13 rpm for the right sprocket and 14 rpm for the left sprocket. The RMS of the lateral deviation is about 0.028 m. These results also approve the applicability of this method in the replicated simulation environment and demonstrate that the controller delivers satisfactory performance.
Table 6 summarizes the results of all previously presented tests, as well as additional trials conducted to assess the robustness of the proposed control method on firm ground. For the repeated trials, the RMS lateral deviation values on asphalt road scenarios ranged between 0.020 m and 0.035 m, with a coefficient of variation (CV) of approximately 21%. For stabilized road scenarios, the RMS lateral deviation values ranged between 0.028 m and 0.045 m, with a CV of approximately 33%, reflecting the greater variability expected under more irregular terrain conditions. The largest lateral deviation was observed in the stabilized parkour test (Scenario 4-2 in Table 6), with a value of 0.045 m. This deviation was mainly due to road surface irregularities, errors in converting GPS position data to Cartesian coordinates, and variations in the friction coefficient under stabilized road conditions, all of which make accurate replication in the simulation environment more challenging. It should be noted that the CV for stabilized road conditions was calculated from only two trials; therefore, it should be interpreted as an indicative measure rather than a statistically robust metric. Nevertheless, the measured ranges and CV values confirm the repeatability of the scenarios, the robustness of the controller in achieving its intended functionality, and the feasibility of applying it, particularly on firm ground surfaces.

8. Discussion and Conclusion

In this study, a slip-based prediction model was developed to enhance the trajectory tracking of unmanned tracked vehicles on firm road conditions by integrating it into a nonlinear model predictive control (NMPC) framework. The core novelty lies in the simplification of the exponential shear displacement formulation, yielding a bounded error but computationally efficient model of slip dynamics. The proposed approach, therefore, achieves a practical balance between accuracy and computational cost, confirming its suitability for high-speed operations in firm terrain conditions.
Comparative analyses demonstrated that the proposed slip-based controller outperformed the kinematic-based model, particularly in high-speed cornering and spiral maneuver scenarios. The slip-based model consistently maintained lateral deviation below 0.06 m RMS in comparative cases, whereas the kinematic model departed from the trajectory at increasing speeds. For a complex trajectory at up to 50 km/h, the lateral deviation remained below 0.08 m RMS, further confirming the robustness of the approach.
Sensitivity analyses were performed to assess the model’s robustness under varying conditions. The results indicated that the model maintains its high performance across different scenarios. Accuracy analyses further highlighted the model’s trend-wise similar performance against the plant model in trajectory tracking tasks. Computational efficiency evaluations indicated that with N = 20 and M = 2, the MPC used about 78% of the available sampling time, demonstrating feasibility for high-performance machines but highlighting the need for tuning in real-time embedded applications.
Validation was carried out through simulation replications using field test data from a five-wheeled tracked vehicle platform on asphalt and stabilized road conditions. The controller reproduced the vehicle’s trajectory, with lateral errors under 0.05 m RMS, and showed good agreement for sprocket speeds and torque trends, with torque estimation errors of up to 18% in asphalt test track conditions. These results confirm the effectiveness and reliability of the proposed framework for firm ground operations.
The improvements presented in this study have promising implications for real-world applications. By incorporating detailed slip dynamics into the prediction model, our approach enhances the reliability of trajectory tracking in unmanned tracked vehicles on firm ground. This advancement is crucial for applications such as unmanned heavy robotic applications and construction vehicles, where precise navigation and control are essential. The model’s ability to maintain low lateral deviations suggests its potential to improve operational efficiency and safety in these sectors.
While our model demonstrates promising results, certain limitations still require further investigation. To extend the usability of the model to more challenging environments such as uneven or deformable terrain, several factors must be addressed. The track–terrain contact mechanics will vary significantly, altering slip generation and distribution outcomes, particularly on irregular or low-cohesion surfaces. In the proposed formulation, track–terrain interaction is expressed in the shear displacement equations through the shear deformation modulus K . This parameter directly influences the exponential term in the force calculation; hence, it determines the effective range of the constant factor K s i m p used in the simplified force calculations. Variations in shear deformation modulus under different terrain properties will, therefore, require either dedicated tuning of K s i m p or preferably an adaptive parameter-updating scheme to maintain the model’s accuracy. As a possible future extension, learning-based estimation techniques could be integrated with the base prediction model to identify K s i m p online, enabling the MPC to adapt in real time to changing surface conditions. Addressing these areas will bridge the gap between simulation results and practical applications.

Author Contributions

Conceptualization, I.G. and S.C.B.; methodology, I.G. and S.C.B.; software, I.G.; investigation, I.G.; data curation, I.G.; writing, I.G.; review and editing, S.C.B.; visualization, I.G.; supervision, S.C.B. All authors have read and agreed to the published version of the manuscript.

Funding

This study is funded by TÜBİTAK (the Scientific and Technological Research Council of Türkiye), under the TÜBİTAK 2244 scholarship program, with the grant number of 119C165.

Data Availability Statement

The datasets presented in this article are not readily available because of the privacy of the ongoing study.

Acknowledgments

The authors appreciate the cooperation of FNSS Savunma Sistemleri A.Ş. in the use of vehicle test data and software.

Conflicts of Interest

Ismail Gocer is an employee at FNSS Savunma Sistemleri A.Ş. and also a PhD candidate at the Graduate School of Science and Engineering, Hacettepe University. S. Caglar Baslamisli is a full-time professor in the Department of Mechanical Engineering, Hacettepe University. The authors declare that the work presented in this paper reflects solely their own views and not those of the affiliated institutions.

Abbreviations

The following abbreviations are used in this manuscript:
MPCModel Predictive Control
CGCenter of Gravity

Appendix A. Comparison of Sprocket Torques Between Referenced Studies and the Plant Model

Table A1. Comparison of sprocket torques at different theoretical turning radii based on the test data [33] and results produced with general theory for skid steering [31] and the plant model [27].
Table A1. Comparison of sprocket torques at different theoretical turning radii based on the test data [33] and results produced with general theory for skid steering [31] and the plant model [27].
Vx
[km/h]
Rth
[m]
Test Data
Outer Spr.
Trq. [Nm]
Test Data
Inner Spr.
Trq. [Nm]
General
Theory
Outer Spr.
Trq. [Nm]
General
Theory
Inner Spr.
Trq. [Nm]
Plant
Model
Outer Spr.
Trq. [Nm]
Plant
Model
Inner Spr.
Trq. [Nm]
7.5519,156−16,84619,156−16,84619,270−17,281
1017,437−15,01517,437−15,01516,871−14,824
2013,926−11,45813,926−11,45813,096−11,011
508522−60378522−60767746−5645
1005468−29805468−29804837−2733
14.2519,060−16,35319,060−16,35319,198−16,790
1017,375−14,91417,375−14,91417,091−15,090
2013,728−11,21013,728−11,21013,394−11,344
508323−57648323−57647934−5841
1005339−27735339−27734944−2842
21.31016,865−14,06016,865−14,06017,091−14,849
2013,356−10,73813,356−10,73813,783−11,744
507962−53217962−53218231−6146
1005055−24055055−24055118−3019
292013,197−10,36213,197−10,36214,127−11,995
507804−50607804−50608626−6542
1004836−20904836−20905361−3263
Table A2. Parameters used in [31] for replicating the turning scenarios for the base study [33].
Table A2. Parameters used in [31] for replicating the turning scenarios for the base study [33].
Parameters
Vehicle mass (kg)25,500
Height of CG (m)1.3
Sprocket radius (m)0.32
Track-ground contact length (m)3.8
Track width (m)0.45
Track pitch (m)0.152
Tread of vehicle (m)2.54
Shear deformation modulus, K (m)0.075
Coefficient of friction between track and ground µ0.9
Coefficient of external motion resistance f r 0.0263

Appendix B. Calculation of Vertical Loads on the Road Wheels

The vertical load under each road wheel is calculated with Equations (A1) and (A5), where F z S t a t i c is the static vertical load, F P r e T e n s is the load decrease due to pretension of the track at the first and last wheels, and F z L a t e r a l A c c is the load transfer due to lateral acceleration. Notice that decreases in vertical load for road wheels, except the first and last wheels, are compensated by the term “ 2 · F P r e T e n s 6 ” in Equations (A3) and (A5).
F z 1 j = F z S t a t i c F P r e T e n s + 1 j + 1 · F z L a t e r a l A c c ,
F z 5 j = F z S t a t i c F P r e T e n s + 1 j + 1 · F z L a t e r a l A c c ,
F z 2 j = F z S t a t i c + 2 · F P r e T e n s 6 + 1 j + 1 · F z L a t e r a l A c c ,
F z 3 j = F z S t a t i c + 2 · F P r e T e n s 6 + 1 j + 1 · F z L a t e r a l A c c ,
F z 4 j = F z S t a t i c + 2 · F P r e T e n s 6 + 1 j + 1 · F z L a t e r a l A c c .
Static vertical load on road wheels is calculated assuming the center of gravity of the vehicle is at geometric center as in Equation (A6), where n is the wheel number per side.
F z S t a t i c = m · g 2 · n .
Load transfer due to lateral acceleration of the vehicle is calculated with Equation (A7), where a y is lateral acceleration, H is the height of the center of gravity (CG) as stated in [27].
F z L a t e r a l A c c = m · a y · H n .

Appendix C. Jacobian Matrix Calculation for MPC Formulation

The “A” state matrix of the slip-based prediction model comprises 8 states; therefore, the Jacobian matrix A J becomes an 8 × 8 matrix, whereas the B J matrix has 8 × 2 dimensions due to the two inputs to the system—left and right sprocket torques. The partial differentiation of each state function with respect to each state then takes the form as in the equations below for the A J matrix:
A J 1,3 = d f 1 d x 3 = d V x d ψ = v y · cos ψ v x · sin ψ
A J 1,4 = d f 1 d x 4 = d V x d v x = cos ψ
A J 1,5 = d f 1 d x 5 = d V x d v y = sin ψ
A J 2,3 = d f 2 d x 3 = d V y d ψ = v x · cos ψ v x · sin ψ
A J 2,4 = d f 2 d x 4 = d V y d v x = sin ψ
A J 2,5 = d f 2 d x 5 = d V y d v y = cos ψ
A J 3,6 = d f 3 d x 6 = d ψ d ψ = 1
A J 4,4 = d f 4 d x 4 = d v ˙ x d v x = F r e s + F z s u m · K s i m p m
A J 4,5 = d f 4 d x 5 = d v ˙ x d v y = ψ ˙
A J 4,6 = d f 4 d x 6 = d v ˙ x d ψ ˙ = 2 · m · v y + K s i m p · T · F z L s u m F z R s u m 2 · m
A J 4,7 = d f 4 d x 7 = d v ˙ x d ω s p r R = K s i m p · r s p r · F z R s u m m
A J 4,8 = d f 4 d x 8 = d v ˙ x d ω s p r L = K s i m p · r s p r · F z L s u m m
A J 5,4 = d f 5 d x 4 = d v ˙ y d v x = ψ ˙
A J 5,5 = d f 5 d x 5 = d v ˙ y d v y = K s i m p · F z s u m m
A J 5,6 = d f 5 d x 6 = d v ˙ y d ψ ˙ = m · v x + K s i m p · i = 1 5 F z i R · l i + F z i L · l i m
A J 6,4 = d f 6 d x 4 = d ψ ¨ d v x = K s i m p · T · F z L s u m F z R s u m 2 · I z z
A J 6,5 = d f 6 d x 5 = d ψ ¨ d v y = K s i m p · i = 1 5 F z i R · l i + F z i L · l i I z z
A J 6,6 = d f 6 d x 6 = d ψ ¨ d ψ ˙ = K s i m p · T 2 · F z s u m + 4 · i = 1 5 F z i R · l i 2 + F z i L · l i 2   4 · I z z
A J 6,7 = d f 6 d x 7 = d ψ ¨ d ω s p r R = K s i m p · T · r s p r · F z R s u m 2 · I z z
A J 6,8 = d f 6 d x 8 = d ψ ¨ d ω s p r L = K s i m p · T · r s p r · F z L s u m 2 · I z z
A J 7,4 = d f 7 d x 4 = d ω ˙ s p r R d v x = K s i m p · r s p r · F z R s u m J
A J 7,6 = d f 7 d x 6 = d ω ˙ s p r R d ψ ˙ = K s i m p · T · r s p r · F z R s u m 2 · J
A J 7,7 = d f 7 d x 7 = d ω ˙ s p r R d ω s p r R = K s i m p · r s p r 2   · F z R s u m J
A J 8,4 = d f 8 d x 4 = d ω ˙ s p r L d v x = K s i m p · r s p r · F z L s u m J
A J 8,6 = d f 8 d x 6 = d ω ˙ s p r L d ψ ˙ = K s i m p · T · r s p r · F z L s u m 2 · J
A J 8,8 = d f 8 d x 8 = d ω ˙ s p r L d ω s p r L = K s i m p · r s p r 2   · F z L s u m J
Similar procedure is applied for B J matrix as with following equations:
B J 7,1 = d f 8 d u 1 = d ω ˙ s p r R d τ s p r R = 1 J
B J 8,2 = d f 8 d u 2 = d ω ˙ s p r L d τ s p r L = 1 J

References

  1. Ly, T.T.K.; Thai, N.H.; Phong, L.T. Design of neural network-PID controller for trajectory tracking of differential drive mobile robot. Vietnam J. Sci. Technol. 2024, 62, 374–386. [Google Scholar]
  2. Snider, J.M. Automatic Steering Methods for Autonomous Automobile Path Tracking. Ph.D. Thesis, Robotics Institute, Carnegie Mellon University, Pittsburgh, PA, USA, 2009. [Google Scholar]
  3. Cibooglu, M.; Karapınar, U.; Söylemez, M.T. Hybrid Controller Approach for Autonomous Ground Vehicle Path Tracking Problem. In Proceedings of the 2017 25th Mediterranean Conference on Control and Automation (MED), Valletta, Malta, 3–6 July 2017. [Google Scholar]
  4. Thrun, S.; Montemerlo, M.; Aron, A.; Diebel, J.; Fong, P.; Gale, J.; Stavens, D. Stanley: The robot that won the DARPA Grand Challenge. J. Field Robot. 2006, 23, 661–692. [Google Scholar] [CrossRef]
  5. Hassan, N.; Saleem, A. Neural Network-Based Adaptive Controller for Trajectory Tracking of Wheeled Mobile Robots. IEEE Access 2022, 10, 13582–13597. [Google Scholar] [CrossRef]
  6. SimCompanion. Available online: https://simcompanion.hexagon.com/customers/s/article/What-New-ATV-2022-3 (accessed on 3 August 2025).
  7. Kong, J.; Pfeiffer, M.; Schildbach, G.; Borrelli, F. Kinematic and Dynamic Vehicle Models for Autonomous Driving Control Design. In Proceedings of the 2015 IEEE Intelligent Vehicles Symposium (IV), Seoul, Republic of Korea, 28 June–1 July 2015; pp. 1094–1099. [Google Scholar] [CrossRef]
  8. Xiang, C.; Peng, H.; Wang, W.; Li, L.; An, Q.; Cheng, S. Path tracking coordinated control strategy for autonomous four in-wheel-motor independent-drive vehicles with consideration of lateral stability. Proc. Inst. Mech. Eng. Part D J. Automob. Eng. 2020, 235, 1023–1036. [Google Scholar] [CrossRef]
  9. Zhang, W.; Wang, Z.; Drugge, L.; Nybacka, M. Evaluating Model Predictive Path Following and Yaw Stability Controllers for Over-Actuated Autonomous Electric Vehicles. IEEE Trans. Veh. Technol. 2020, 69, 12807–12821. [Google Scholar] [CrossRef]
  10. Mahalingam, I.; Padmanabhan, C. A novel alternate multibody model for the longitudinal and ride dynamics of a tracked vehicle. Veh. Syst. Dyn. 2019, 59, 433–457. [Google Scholar] [CrossRef]
  11. Ma, Z.-D.; Perkins, N.C. A Track-Wheel-Terrain Interaction Model for Dynamic Simulation of Tracked Vehicles. Veh. Syst. Dyn. 2002, 3, 401–421. [Google Scholar]
  12. Wong, J.Y. Dynamics of Tracked Vehicles. Veh. Syst. Dyn. 1997, 28, 197–219. [Google Scholar] [CrossRef]
  13. Çalışkan, K. Modelling and Simulation of Tracked Vehicle Dynamics. Ph.D. Thesis, Middle East Technical University, Ankara, Türkiye, 2009. [Google Scholar]
  14. Zhou, L.; Wang, G.; Sun, K.; Li, X. Trajectory Tracking Study of Track Vehicles Based on Model Predictive Control. J. Mech. Eng. /Stroj. Vestnik 2019, 65, 329–342. [Google Scholar] [CrossRef]
  15. Zhao, Z.; Liu, H.; Chen, H.; Xu, S.; Lang, W. Tracking Control of Unmanned Tracked Vehicle in Off-road Conditions with Large Curvature. In Proceedings of the IEEE Intelligent Transportation Systems Conference (ITSC), Auckland, New Zealand, 27–30 October 2019. [Google Scholar] [CrossRef]
  16. Zhao, Z.; Liu, H.; Chen, H.; Hu, J.; Guo, H. Kinematics-aware model predictive control for autonomous high-speed tracked vehicles under the off-road conditions. Mech. Syst. Signal Process. 2019, 123, 333–350. [Google Scholar] [CrossRef]
  17. Tao, J.; Liu, H.; Li, Y.; Guan, H.; Liu, J.; Chen, H. Design of Trajectory Tracking Controller of Unmanned Tracked Vehicles Based on Torque Control. In Proceedings of the IEEE International Conference on Unmanned Systems (ICUS), Beijing, China, 15–17 October 2021. [Google Scholar] [CrossRef]
  18. Maclaurin, B. A skid steering model using the Magic Formula. J. Terramech. 2011, 48, 247–263. [Google Scholar] [CrossRef]
  19. Liang, J.; Tian, Q.; Feng, J.; Pi, D.; Yin, G. A Polytopic Model-Based Robust Predictive Control Scheme for Path Tracking of Autonomous Vehicles. IEEE Trans. Intell. Veh. 2024, 9, 3928–3939. [Google Scholar] [CrossRef]
  20. Liang, J.; Lu, Y.; Wang, F.; Feng, J.; Pi, D.; Yin, G.; Li, Y. ETS-Based Human–Machine Robust Shared Control Design Considering the Network Delays. IEEE Trans. Autom. Sci. Eng. 2024, 22, 17501–17511. [Google Scholar] [CrossRef]
  21. Li, B.; Pan, Z.; Liu, J.; Zhou, S.; Liu, S.; Chen, S.; Wang, R. Integrated Control of a Wheel–Track Hybrid Vehicle Based on Adaptive Model Predictive Control. Machines 2024, 12, 485. [Google Scholar] [CrossRef]
  22. Zhan, J.; Li, W.; Wang, J.; Xiong, S.; Wu, X.; Shi, W. Research on Trajectory Planning and Tracking Algorithm of Crawler Paver. Machines 2024, 12, 650. [Google Scholar] [CrossRef]
  23. Inal, T.T.; Cansever, G.; Yalçın, B.; Çetin, G.; Hartavi, A.E. Enhanced Energy Efficiency through Path Planning for Off-Road Missions of Unmanned Tracked Electric Vehicle. Vehicles 2024, 6, 1027–1050. [Google Scholar] [CrossRef]
  24. Strawa, N.; Ignatyev, D.I.; Zolotas, A.C.; Tsourdos, A. On-Line Learning and Updating Unmanned Tracked Vehicle Dynamics. Electronics 2021, 10, 187. [Google Scholar] [CrossRef]
  25. Fan, J.; Yan, P.; Li, R.; Liu, Y.; Wang, F.; Liu, Y.; Chen, C. Decoupled Adaptive Motion Control for Unmanned Tracked Vehicles in the Leader-Following Task. World Electr. Veh. J. 2024, 15, 239. [Google Scholar] [CrossRef]
  26. Zhang, R.; Zhou, W.; Liu, H.; Gong, J.; Chen, H.; Khajepour, A. Similarities between Wheels and Tracks: A “Tire Model” for Tracked Vehicles. IEEE Trans. Veh. Technol. 2024, 73, 16416–16431. [Google Scholar] [CrossRef]
  27. Ozdemir, M.N.; Unlusoy, Y.S. Steering Dynamics of Tracked Vehicles. Master’s Thesis, Middle East Technical University, Ankara, Türkiye, 2016. [Google Scholar]
  28. Garber, M.; Wong, J.Y. Prediction of ground pressure distribution under tracked vehicles—I. An analytical method for predicting ground pressure distribution. J. Terramech. 1981, 18, 1–23. [Google Scholar] [CrossRef]
  29. Weiss, K.R. Skid Steering. Proc. Inst. Mech. Eng. Part D J. Automob. Eng. 1971, 22–25. [Google Scholar]
  30. Kitano, M.; Jyozaki, H. A theoretical analysis of steerability of tracked vehicles. J. Terramech. 1976, 13, 241–258. [Google Scholar] [CrossRef]
  31. Wong, J.Y.; Chiang, C.-F. A general theory for skid steering of tracked vehicles on firm ground. Proc. Inst. Mech. Eng. Part D J. Automob. Eng. 2001, 215, 343–355. [Google Scholar] [CrossRef]
  32. Chiang, C.-F. Handling Characteristics of Tracked Vehicles on Non-Deformable Surfaces. Master’s Thesis, Ottawa-Carleton Institute for Mechanical and Aerospace Engineering, Department of Mechanical and Aerospace Engineering, Ottawa, ON, Canada, June 1999. [Google Scholar]
  33. Ehlert, W.; Hug, B.; Schmid, I.C. Field measurements and analytical models as a basis of test stand simulation of the turning resistance of tracked vehicles. J. Terramech. 1992, 29, 57–69. [Google Scholar] [CrossRef]
  34. Zou, Y.; Sun, F.; Hu, X.; Guzzella, L.; Peng, H. Combined optimal sizing and control for a hybrid tracked vehicle. Energies 2012, 5, 4697–4710. [Google Scholar] [CrossRef]
  35. ISO 4138:2021; Passenger Cars—Steady-State Circular Driving Behaviour—Open-Loop Test Methods. International Organization for Standardization: Geneva, Switzerland, 2021.
  36. Çiloglu, Ç.; Kutluay, E. Performance Improvement of Pure Pursuit Algorithm via Online Slip Estimation for Off-Road Tracked Vehicle. Sensors 2025, 25, 4242. [Google Scholar] [CrossRef] [PubMed]
Figure 2. (a) Simple kinematic model (b) and sliding kinematic model.
Figure 2. (a) Simple kinematic model (b) and sliding kinematic model.
Machines 13 00817 g002
Figure 3. Shear displacement-based plant model [27]: (a) kinematics of the model; (b) kinematics of the discretized track pads.
Figure 3. Shear displacement-based plant model [27]: (a) kinematics of the model; (b) kinematics of the discretized track pads.
Machines 13 00817 g003
Figure 4. Comparison of sprocket torques at different theoretical turning radii in logarithmic scale based on the test data [33] and results produced with the general theory [31] and plant model [27]: (a) Results for 7.5 km/h; (b) Results for 14.2 km/h; (c) Results for 21.3 km/h; (d) Results for 29 km/h.
Figure 4. Comparison of sprocket torques at different theoretical turning radii in logarithmic scale based on the test data [33] and results produced with the general theory [31] and plant model [27]: (a) Results for 7.5 km/h; (b) Results for 14.2 km/h; (c) Results for 21.3 km/h; (d) Results for 29 km/h.
Machines 13 00817 g004
Figure 5. Change of K s i m p = f e x p / V s function with respect to changes of V s and V t for the mid road wheel.
Figure 5. Change of K s i m p = f e x p / V s function with respect to changes of V s and V t for the mid road wheel.
Machines 13 00817 g005
Figure 6. Layout of the proposed prediction model.
Figure 6. Layout of the proposed prediction model.
Machines 13 00817 g006
Figure 7. Flowchart of MPC framework.
Figure 7. Flowchart of MPC framework.
Machines 13 00817 g007
Figure 8. Scenario 1 (R40: increasing speed): (a) trajectory results; (b) tracking errors; (c) longitudinal velocity tracking results.
Figure 8. Scenario 1 (R40: increasing speed): (a) trajectory results; (b) tracking errors; (c) longitudinal velocity tracking results.
Machines 13 00817 g008
Figure 9. Scenario 2 (10 km/h spiral motion): (a) trajectory results; (b) tracking errors; (c) longitudinal velocity tracking results.
Figure 9. Scenario 2 (10 km/h spiral motion): (a) trajectory results; (b) tracking errors; (c) longitudinal velocity tracking results.
Machines 13 00817 g009
Figure 10. Scenario 3: Fictitious complex drive track.
Figure 10. Scenario 3: Fictitious complex drive track.
Machines 13 00817 g010
Figure 11. Results of Scenario 3: (a) tracking errors; (b) longitudinal velocity tracking results.
Figure 11. Results of Scenario 3: (a) tracking errors; (b) longitudinal velocity tracking results.
Machines 13 00817 g011
Figure 12. Trajectory following results of Scenario 3: (a) zoom region 1; (b) zoom region 2; (c) zoom region 3; (d) zoom region 4.
Figure 12. Trajectory following results of Scenario 3: (a) zoom region 1; (b) zoom region 2; (c) zoom region 3; (d) zoom region 4.
Machines 13 00817 g012
Figure 13. Normalized torque outputs of MPC controller for Scenario 3.
Figure 13. Normalized torque outputs of MPC controller for Scenario 3.
Machines 13 00817 g013
Figure 14. Parameter sensitivity friction coefficient: (a) trajectories of vehicles for different friction coefficient values; (b) velocity profiles for different friction coefficient values.
Figure 14. Parameter sensitivity friction coefficient: (a) trajectories of vehicles for different friction coefficient values; (b) velocity profiles for different friction coefficient values.
Machines 13 00817 g014
Figure 15. Torque input for model comparison.
Figure 15. Torque input for model comparison.
Machines 13 00817 g015
Figure 16. Trajectory outputs of the plant model and prediction model for Scenario 1.
Figure 16. Trajectory outputs of the plant model and prediction model for Scenario 1.
Machines 13 00817 g016
Figure 17. Comparison of state outputs of the plant model and prediction model for Scenario 1: (a) velocity; (b) yaw rate; (c) speed of left sprocket; (d) speed of right sprocket.
Figure 17. Comparison of state outputs of the plant model and prediction model for Scenario 1: (a) velocity; (b) yaw rate; (c) speed of left sprocket; (d) speed of right sprocket.
Machines 13 00817 g017
Figure 18. Instrumentation on the sprocket driving shaft for measurements of shaft speed and torque.
Figure 18. Instrumentation on the sprocket driving shaft for measurements of shaft speed and torque.
Machines 13 00817 g018
Figure 19. Top view of the asphalt test track (due to sensitive information, the test track view is cropped).
Figure 19. Top view of the asphalt test track (due to sensitive information, the test track view is cropped).
Machines 13 00817 g019
Figure 20. Results of Test Scenario 1: GPS coordinates vs. reproduced MPC results.
Figure 20. Results of Test Scenario 1: GPS coordinates vs. reproduced MPC results.
Machines 13 00817 g020
Figure 21. Results of Test Scenario 1—lateral deviation.
Figure 21. Results of Test Scenario 1—lateral deviation.
Machines 13 00817 g021
Figure 22. Results of Test Scenario 1—comparison of test vs. reproduced data: (a) velocity profile; (b) sprocket speeds; (c) normalized sprocket torque.
Figure 22. Results of Test Scenario 1—comparison of test vs. reproduced data: (a) velocity profile; (b) sprocket speeds; (c) normalized sprocket torque.
Machines 13 00817 g022
Figure 23. Results of Test Scenario 2: GPS coordinates vs. reproduced MPC results: (a) top view; (b) trajectory change with respect to time.
Figure 23. Results of Test Scenario 2: GPS coordinates vs. reproduced MPC results: (a) top view; (b) trajectory change with respect to time.
Machines 13 00817 g023
Figure 24. Results of Test Scenario 2—lateral deviation.
Figure 24. Results of Test Scenario 2—lateral deviation.
Machines 13 00817 g024
Figure 25. Results of Test Scenario 2—comparison of test vs. reproduced data: (a) velocity profile; (b) sprocket speeds; (c) normalized sprocket torque.
Figure 25. Results of Test Scenario 2—comparison of test vs. reproduced data: (a) velocity profile; (b) sprocket speeds; (c) normalized sprocket torque.
Machines 13 00817 g025
Figure 26. Top view of the stabilized test parkour [36].
Figure 26. Top view of the stabilized test parkour [36].
Machines 13 00817 g026
Figure 27. Results of test scenario on stabilized roads: GPS coordinates vs. reproduced MPC results.
Figure 27. Results of test scenario on stabilized roads: GPS coordinates vs. reproduced MPC results.
Machines 13 00817 g027
Figure 28. Results of test scenario on stabilized parkour: (a) velocity profile comparison; (b) sprocket speed comparison; (c) lateral deviation.
Figure 28. Results of test scenario on stabilized parkour: (a) velocity profile comparison; (b) sprocket speed comparison; (c) lateral deviation.
Machines 13 00817 g028
Table 1. Applied vehicle dataset [27] and MPC settings.
Table 1. Applied vehicle dataset [27] and MPC settings.
ItemSymbolValue
Vehicle Massm13,200 [kg]
Number of Wheels per Siden5
Yaw InertiaIzz22,325 [kgm^2]
Height of CGH1.03 [m]
Tread of the VehicleT2.24 [m]
Length of Track ContactL2.67 [m]
Friction Coefficient μ 0.9
Shear Deformation Modulus K 0.075
Rolling Resistance Coeff. f R e s 0.0263
Sampling TimeTs0.05
Prediction HorizonN20
Control HorizonM2
Simulation Step Sizestpsz0.01
Table 2. Trajectory tracking errors of the slip-based model with respect to changing K s i m p simplification factor.
Table 2. Trajectory tracking errors of the slip-based model with respect to changing K s i m p simplification factor.
K s i m p Lateral
Deviation Rms [m]
Yaw
Angle Error Rms
[rad]
0.50.0620.029
10.0490.029
1.50.0150.028
20.0690.027
2.50.1150.027
30.1520.026
3.50.1810.026
Table 3. RMS errors of simulations with applied prediction models.
Table 3. RMS errors of simulations with applied prediction models.
Kinematic
Prediction Model
Lateral Deviation Rms
[m]
Yaw Angle Error Rms
[rad]
Long. Vel. Error Rms
[m/s]
R20 Steady 20 km/h0.1930.0450.193
Scen.1: R 40 Incr. Speed1.3430.0700.407
Scen.2: 10 km/h Spiral0.2250.0710.169
Slip-Based
Prediction Model
Lateral Deviation Rms
[m]
Yaw Angle Error Rms
[rad]
Long. Vel. Error Rms
[m/s]
R20 Steady 20 km/h0.0110.0390.165
Scen.1: R 40 Incr. Speed0.0150.0280.229
Scen.2: 10 km/h Spiral0.0570.0540.115
Table 4. Ratio of actual lateral acceleration to theoretical limit.
Table 4. Ratio of actual lateral acceleration to theoretical limit.
µTheoretical Limit
for Lateral Acc. [g]
Reached
Lateral Acc. [g]
Percentage to Limit
Lateral Acc [%]
0.900.900.7482
0.700.700.5579
0.500.500.3774
0.300.300.1860
0.200.200.0735
Table 5. The sensitivity analysis for MPC-specific parameters for Scenario 1.
Table 5. The sensitivity analysis for MPC-specific parameters for Scenario 1.
Slip-Based
Prediction Model
Sampling
Time-Ts
[s]
Lateral
Deviation Rms
[m]
Yaw Angle
Error Rms
[rad]
Long. Vel.
Error Rms
[m/s]
tavg_step
[s]
tavg_step
/
Ts
N: 20 M: 10.050.0110.0580.3390.04079%
N: 20 M: 20.0150.0280.2290.03978%
N: 10 M: 10.050.0680.0170.1230.02245%
N: 10 M: 20.1040.0430.1140.02550%
N: 10 M: 10.10.1030.0120.3800.02727%
N: 10 M: 20.0760.0130.3010.03030%
Table 6. Summary table for all conducted tests for verification of trajectory tracking control (* additional tests).
Table 6. Summary table for all conducted tests for verification of trajectory tracking control (* additional tests).
Test Scen.Test TrackDesired
Steady
Speed
[km/h]
Average
Test
Velocity
[km/h]
Direction
/
Cycle Number
Lateral
Deviation Rms
[m]
Long.
Vel. Error
Rms
[km/h]
1-1Asphalt Track15 km/h12.3Test Track to Base/10.0221.145
1-2 *Asphalt Track15 km/h18.0Base to Test Track/10.0351.755
2-1Asphalt Track40 km/h36.0CCW/30.0251.433
2-2 *Asphalt Track40 km/h35.8CW/30.0291.314
3-1 *Asphalt Track30 km/h29.3CCW/30.0241.113
3-2 *Asphalt Track30 km/h29.7CW/30.0201.321
4-1Stabilized Parkour20–25 km/h17.4CW/10.0280.919
4-2 *Stabilized Parkour20–25 km/h19.0CCW/10.0452.567
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Gocer, I.; Baslamisli, S.C. A Slip-Based Model Predictive Control Approach for Trajectory Following of Unmanned Tracked Vehicles. Machines 2025, 13, 817. https://doi.org/10.3390/machines13090817

AMA Style

Gocer I, Baslamisli SC. A Slip-Based Model Predictive Control Approach for Trajectory Following of Unmanned Tracked Vehicles. Machines. 2025; 13(9):817. https://doi.org/10.3390/machines13090817

Chicago/Turabian Style

Gocer, Ismail, and Selahattin Caglar Baslamisli. 2025. "A Slip-Based Model Predictive Control Approach for Trajectory Following of Unmanned Tracked Vehicles" Machines 13, no. 9: 817. https://doi.org/10.3390/machines13090817

APA Style

Gocer, I., & Baslamisli, S. C. (2025). A Slip-Based Model Predictive Control Approach for Trajectory Following of Unmanned Tracked Vehicles. Machines, 13(9), 817. https://doi.org/10.3390/machines13090817

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