Next Article in Journal
Quadratic Programming Vision-Based Control of a Scale-Model Autonomous Vehicle Navigating in Intersections
Previous Article in Journal
RM-Act: A Novel Modular Harmonic Actuator
Previous Article in Special Issue
VS-SLAM: Robust SLAM Based on LiDAR Loop Closure Detection with Virtual Descriptors and Selective Memory Storage in Challenging Environments
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

FVSMPC: Fuzzy Adaptive Virtual Steering Coefficient Model Predictive Control for Differential Tracked Robot Trajectory Tracking

1
School of Mechanical Engineering and Automation, Beihang University, Beijing 100191, China
2
Laboratory of Aerospace Servo Actuaion and Transmission, Beijing 100191, China
*
Authors to whom correspondence should be addressed.
Actuators 2025, 14(10), 493; https://doi.org/10.3390/act14100493
Submission received: 31 August 2025 / Revised: 7 October 2025 / Accepted: 10 October 2025 / Published: 12 October 2025

Abstract

Differential tracked robots play a crucial role in various modernized work scenarios such as smart industry, agriculture, and transportation. However, these robots frequently encounter substantial challenges in trajectory tracking, attributable to substantial initial errors and dynamic environments, which result in slow convergence rates, cumulative errors, and diminished tracking precision. To address these challenges, this paper proposes a fuzzy adaptive virtual steering coefficient model predictive control (FVSMPC) algorithm. The FVSMPC algorithm introduces a virtual steering coefficient into the robot’s kinematic model, which is adaptively adjusted using fuzzy logic based on real-time positional error and velocity. This approach not only enhances the robot’s ability to quickly correct large errors but also maintains stability during tracking.The nonlinear kinematic model undergoes linearization via a Taylor expansion and is subsequently formulated as a quadratic programming problem to facilitate efficient iterative solutions. To validate the proposed control algorithm, a simulation environment was constructed and deployed on a real prototype for testing. Results demonstrate that compared to the baseline algorithm, the proposed algorithm performs excellently in trajectory tracking tasks, avoids complex parameter tuning, and exhibits high accuracy, fast convergence, and good stability. This work provides a practical and effective solution for improving the trajectory tracking performance of differential tracked robots in complex environments.

1. Introduction

Over the past few decades, differential tracked robots have been widely applied in various modernized work scenarios such as smart industry, smart agriculture, and smart transportation. They exhibit excellent terrain adaptability, and their ability to turn on the spot provides enhanced flexibility in complex environments [1]. With continued advancement in intelligence levels, robots are becoming increasingly adept at environmental perception, motion planning, and trajectory tracking control [2]. Differential tracked robots belong to the category of incomplete systems, characterized by a set of non-integrable first-order differential constraints. These limitations stem from the assumption that the robot does not slip during movement [3]. The non-integrating nature of the system makes it difficult to quickly and effectively correct lateral position errors caused by external disturbances or dynamic environments. Aggressive control parameters can cause oscillations and overshoot, making trajectory tracking a challenging task.
Consequently, the development of an appropriate controller for differential tracked mobile robots that ensures precise tracking under significant error conditions remains a formidable challenge. Existing path tracking control methods can be categorized into two types based on whether a robot model is used. Model-free control methods do not require the establishment of a robot model, ignore robot characteristics, and directly calculate the steering angle based on the deviation between the robot and the reference path, including PID control methods [4] and fuzzy control methods [5], etc. Model-based methods require the establishment of an actual robot model, including pure tracking control methods [6,7], Stanley control methods [8], model predictive control (MPC) [9], Linear Quadratic Regulator (LQR) methods [10], and sliding mode control methods [11,12].
MPC is widely used in trajectory tracking, path planning, and obstacle avoidance [13,14,15,16,17,18]. The MPC principle is based on the robot model and current motion state to predict the driving trajectory within the predicted time domain, and calculates the optimal control quantities online through rolling optimization. Jiawei Tang [19] considered both the manifold constraints and kinematic constraints of the robot simultaneously; the error dynamics of the trajectory tracking of the wheeled mobile robot were derived. Subsequently, the tracking control problem was made convex by utilizing the relationship between Lie groups and Lie algebras, thereby enabling efficient problem-solving. Kayacan et al. [20] designed a linear model predictive controller based on the trajectory tracking error model, combining feedforward control and robust control to achieve tracking of both linear and curved target trajectories. Xu et al. [21] used future road curvature as dynamic disturbance input, augmented the vehicle model matrix, and solved for the optimal steering control law. They optimized the feedback control of the corresponding tracking error and the feedforward control of future road curvature, and analyzed the closed-loop stability of the system. Chen et al. [22] based their work on the robot dynamics model, employed a sliding mode variable structure algorithm and control system for path tracking control of the robot, designed a Lyapunov function to ensure system convergence, and experimentally verified the excellent path tracking performance. The computational burden and requirement for precise models pose major challenges for MPC, prompting researchers to explore integration with fuzzy logic systems and adaptive techniques to enhance its robustness and applicability. For ground mobile robots (GMRs) featuring independent three-axis six-wheel drive and four-wheel independent steering, studies have constructed dynamic models and effectively addressed low-speed trajectory tracking using MPC technology. For high-speed conditions, an Artificial Neural Network Fuzzy Inference System (ANFIS) was integrated for compensation, improving trajectory tracking accuracy and robustness [23]. For incomplete mobile robots, research proposed MPC-based fuzzy predictive control to overcome traditional MPC challenges in computational complexity, parameter tuning, and jitter suppression, while enhancing tracking precision [24]. Adaptive MPC is crucial for addressing positioning fluctuations and model uncertainties in mobile robots. One study proposed adaptive MPC with positioning fluctuation estimation to balance control performance and sensitivity to positioning errors, effectively preventing severe oscillations and poor trajectory tracking [25]. For two-wheeled mobile robots with unknown inertia, researchers employed an adaptive MPC (AMPC) framework to guide target point and directional movements. Dynamic equations were derived using the Lagrange method, with input obtained at each time step via MPC utilizing nominal parameters [26]. Furthermore, an adaptive MPC scheme was proposed for omnidirectional mobile robots with friction compensation and incremental input constraints. This scheme employs a cascaded structure, where the outer loop implements kinematics-based control and the inner loop utilizes adaptive linear MPC design [27]. Within the Koopman operator framework, research has also explored learning-based MPC for handling nonlinear systems with time-varying parameters. This approach enhances adaptability to time-varying parameters by learning multi-core Koopman operator models, which is crucial for systems with model bias [28].
In summary, although model-free control methods such as PID and fuzzy control are widely applied, they often struggle with large initial errors and dynamic environments. Model-based approaches, such as MPC, demonstrate significant potential, but may involve substantial computational demands and require complex parameter tuning. To address these challenges, we propose a model predictive control algorithm based on fuzzy control of the virtual steering coefficient. First, a kinematic model is established that incorporates a virtual steering coefficient. The error model is derived and linearized, then converted into a quadratic programming problem for the rolling-horizon solution. Second, fuzzy membership rules for the virtual steering coefficient are designed based on position error and driving speed to dynamically adjust the coefficient. The contributions of this study are twofold:
  • It enhances convergence speed and tracking accuracy while eliminating the complex process of tuning multiple parameters. This is particularly crucial during dynamic tracking, where the robot must adapt to changing conditions in real time.
  • The effectiveness of the proposed algorithm was validated through simulations and physical experiments, demonstrating superior performance compared to traditional MPC and PID algorithms. Our results show that FVSMPC achieves faster convergence rates, lower average position errors, and better stability, especially under conditions of large initial errors.
The structure of this paper is as follows: Section 1 presents the background and significance of the research. Section 2 covers the methodology, including the description of the problem, the differential kinematic model of the virtual steering coefficient, the derivation of the linear error model, the quadratic optimization solution for the rolling time domain, and the adaptive steering coefficient based on fuzzy reasoning. Section 3 presents simulation and experimental results. Section 4 discusses the findings, and Section 5 concludes the study.

2. Methods

2.1. Problem Description

Our subject is a differential tracked robot named Climber (Figure 1). Each side is driven by a brushless DC motor. Motor drivers receive speed commands directly from the computing unit via the CAN bus, which drives the motors to rotate. The power is then transmitted to the tracks through a reduction gear mechanism. The LiDAR sensor is a Robosence Helios 32, the IMU sensor is a WIT 9073, the computing unit is an NVIDIA Orin, and the CPU is an ARM Cortex-A78, with 64 GB of memory, running Ubuntu and the ROS1 system.
The following assumptions are made prior to the problem description:
  • No-slip assumption: It is assumed that no slippage occurs during the robot’s motion. This is a common assumption in differential-based tracking robot kinematic models, ensuring that the robot’s motion can be precisely described by its kinematic equations.
  • Accurate positioning data assumption: Sensors used for state estimation (e.g., LiDAR, IMU) are assumed to provide accurate and reliable measurements. This assumption is essential to ensure that the real-time position error and velocity used in the fuzzy logic controller are precise.
The trajectory tracking problem is described as shown in Figure 2: Given a predefined desired trajectory, design an MPC tracking control strategy to predict the robot’s trajectory within the predictive control horizon. Compute the optimal control commands for the robot such that its actual position closely approximates the reference position while ensuring that the tracking error converges to zero within a finite time or remains within a small tolerance range.

2.2. Differential Kinematic Model of Virtual Steering Coefficient

The classic kinematic model of a tracked robot is shown in the Figure 3. This kinematic model can describe the behavior of differential-drive tracked robots during straight-line motion, curved paths, on-the-spot turns, and right-angle turns. Notably, on-the-spot turns and right-angle turns pose significant challenges for non-differential-drive mobile robots. Such robots possess a turning radius greater than zero. However, our research focuses on differential tracked robots capable of differential motion in place. During in-place turns, the left and right tracks operate at equal speeds but opposite directions, i.e., v l = v R . This principle also applies during right-angle turns. Substituting the left and right track speeds into the kinematic model reveals that the robot’s x and y components become zero, with only the yaw angle varying. Thus, the proposed kinematic model can accommodate these special cases.
The quantity of state s of a robot is defined as composed of the horizontal and vertical coordinates of the robot and the angle of yaw.
s = x y φ
Generally, the control quantities based on the kinematic model are the linear velocity and the angular velocity of the vehicle body. In this paper, the control quantity u of the robot is defined as the linear velocity of the left and right tracks and the virtual steering coefficient α .
u = v L v R α
The virtual steering coefficient is used to adjust the robot’s steering response capability, with the kinematic relationship expressed by Equation (3):
d s d t = ( v L + v R ) 2 cos φ ( v L + v R ) 2 sin φ v R v L B α = f ( s , u )
Here, α is the virtual steering coefficient, which adjusts the robot’s steering response. A higher value of α increases the robot’s sensitivity to steering commands, while a lower value of α reduces it. The range of α is typically between 0.1 and 6, as determined by simulation and experimental tuning. The left and right track speeds in the control variables are provided by the upper-level trajectory generation module, and α varies according to the strategy in the next section. The reference trajectory satisfies the kinematic model of the tracked robot, as shown in Equation (4):
s r ˙ = f ( s r , u r )
s r is the sequence of system states generated by the initial state s r ( 0 ) within the prediction domain under the action of a series of reference control inputs u r ( k ) , satisfying the kinematic equations of the system mentioned above. Moreover, in the reference state sequence, starting from any s r as the initial state and applying the remaining reference control inputs u r , the equations are still satisfied.

2.3. Error Model Linearization

Based on the fundamental concept of Taylor series expansion, using any state from the reference trajectory as the initial state and applying the corresponding residual reference control input, a Taylor expansion is performed under this special condition while neglecting higher-order terms to obtain Equation (5):
s ˙ = f ( s r , u r ) + f s r ( s s r ) + f u r ( u u r )
The above equation eliminates the nonlinear terms in the kinematic equation. Subtracting the two equations yields the error state space equation (Equation (6)):
s ˜ ˙ = f s r ( s s r ) + f u r ( u u r ) = a s ˜ + b u ˜
where
a = f s r = 0 0 v L + v R 2 sin ( φ ) 0 0 v L + v R 2 cos ( φ ) 0 0 0 r
b = f u r = cos φ 2 cos φ 2 0 sin φ 2 sin φ 2 0 α B α B v R v L B r
Using the forward Euler method, the discretized kinematic model is obtained (Equation (7)). T represents the time step:
s ˜ ( k + 1 ) = s ˜ ( k ) + s ˜ ˙ ( k ) · T = ( a T + I ) s ˜ ( k ) + b T u ˜ ( k ) = A s ˜ ( k ) + B u ˜ ( k )
where
A = 1 0 T v L + v R 2 sin ( φ ) 0 1 T v L + v R 2 cos ( φ ) 0 0 1 r
B = T cos φ 2 T cos φ 2 0 T sin φ 2 T sin φ 2 0 T α B T α B T v R v L B r

2.4. Solving Rolling Time Domain Quadratic Programming Problems

The cost function for tracking is the following.
J k = j = 1 N p s ˜ T ( k + j | k ) Q s ˜ ( k + j | k ) + u ˜ T ( k + j 1 | k ) R u ˜ ( k + j 1 | k )
where
Q = q x 0 0 0 q y 0 0 0 q φ = 1 0 0 0 1 0 0 0 0.05
R = r v R 0 0 0 r v L 0 0 0 r α = 0.1 0 0 0 0.1 0 0 0 0.1
N p denotes the length of the prediction time horizon. The cost function for trajectory tracking control consists of two parts: state deviation cost and control deviation cost. Q and R are the state weight matrix and the control weight matrix, respectively, and are set to be positive definite matrices, to ensure that the subsequent quadratic programming problem has a solution. These matrices are selected to balance the trade-off between the state deviation and the control effort. The state deviation cost ensures that the robot closely follows the reference trajectory, while the control deviation cost prevents excessive control input that could lead to oscillations.
The cost function is transformed into the standard quadratic programming problem form below to facilitate subsequent solutions. According to the above state space equation, the state recurrence formula can be obtained:
s ˜ ( k + N p ) = A k + N p 1 s ( k + N p 1 ) + B k + N p 1 u ( k + N p 1 ) = j = 0 N p 1 A k + j · s ˜ ( k ) + j = 1 N p 1 A k + j · B k · u ˜ ( k ) + j = 2 N p 1 A k + j · B k + 1 · u ˜ ( k + 1 ) + + j = N p 1 N p 1 A k + j · B k + N p 2 · u ˜ ( k + N p 2 ) + B k + N p 1 · u ˜ ( k + N p 1 )
Derive the relationship between the state variables and control variables within the prediction domain:
S ( k ) = M k · s ˜ ( k ) + N k · U ( k )
where
S ( k ) = s ˜ ( k + 1 | k ) s ˜ ( k + 2 | k ) s ˜ ( k + N p | k ) , U ( k ) = u ˜ ( k | k ) u ˜ ( k + 1 | k ) u ˜ ( k + N p 1 | k ) , M k = A k A k + 1 A k j = 0 N p 1 A k + j , N k = B k 0 0 0 0 A k + 1 B k B k + 1 0 0 A k + 2 A k + 1 B k A k + 2 B k B k + 2 j = 1 N p 1 A k + j B k j = 2 N p 1 A k + j B k + 1 j = N p 1 N p 1 A k + j B k + N p 2 B k + N p 1
Combining this formula, the cost function can be transformed into the following formula:
J k = S T ( k ) Q B S ( k ) + U T ( k ) R B U ( k )
Among them, the weight matrix is a single time-step weight matrix obtained through the Kronecker product, assuming that the weight matrix within the prediction domain does not change:
Q B = k r o n ( Q , I N p ) = Q 0 0 0 Q 0 0 0 Q N p × N p
R B = k r o n ( R , I N p ) = R 0 0 0 R 0 0 0 R N p × N p
Taking the control quantity within the prediction domain as the quadratic programming solution object, further simplifying the above equation, and ignoring the constant terms that do not affect the cost function, we obtain Equation (12):
J k = U T ( N k T Q B N k + R B ) U + 2 U T N k T Q B M k s ˜ ( k )
The corresponding standard form of quadratic programming is as follows:
min J = 1 2 U T H U + U T L
s . t . U m i n U U m a x
H = 2 ( N k T Q B N k + R B ) , L = 2 N k T Q B M k s ˜ ( k )
The quadratic programming problem converted to a general form is solved using the ECOS solver to obtain the optimal solution at each sampling time point, thereby obtaining the optimal control sequence. The value of the control deviation solution for the first control cycle plus the corresponding reference control quantity is equal to the speed of the left and right tracks and the virtual steering coefficient of the current control cycle. At this point, the derivation of the predictive controller of the virtual steering coefficient model (VSMPC) is complete.

2.5. Adaptive Virtual Steering Coefficient Based on Fuzzy Reasoning

As derived in the previous section, the magnitude of the virtual steering coefficient directly influences the robot’s response to the error model, thus affecting the performance of the trajectory tracking. Therefore, this section introduces an adaptive virtual steering coefficient calculation method. Based on fuzzy logic theory, it updates the robot’s desired virtual steering coefficient by adaptively computing future values. This improves the robot error response capability and minimizes cumulative lateral error during periods of large errors.
A straight-line path is selected as the reference path, with an initial position error of 0.2 m. We found that below 0.1, the algorithm responds very slowly to errors, while above 6, significant overshoot occurs in the trajectory. Therefore, we set the value range between 0.1 and 6. The trajectory tracking error is shown in Figure 4.
Based on the simulation results, the controller can quickly reduce the lateral error and approach the desired trajectory. The higher the virtual steering coefficient, the faster the robot responds to errors. However, an overshoot occurs after reaching the desired trajectory. which then gradually aligns with the desired trajectory. Therefore, by dynamically adjusting the virtual steering coefficient, increasing it when the error is large, and decreasing it when the error decreases, we can enhance the controller’s ability to respond to large errors while reducing overshoot and minimizing position error. Based on the simulation results above, the position error and the average speed within the future prediction time domain are selected as input to the fuzzy controller, and the desired virtual steering coefficient is selected as output to the fuzzy controller. Fuzzy rules are designed as follows:
  • Rule 1: When the average speed within the future prediction time domain is small and the position error is large, the desired virtual steering coefficient should be increased to enhance the error response speed. This rule ensures that the robot can quickly correct large errors, which is crucial to maintain stability and reduce cumulative errors.
  • Rule 2: When the position error is small and the average speed within the future prediction time domain is large, the desired virtual steering coefficient should decrease to ensure the stability of the tracking process. This rule helps to avoid overshoots and oscillations, ensuring smooth and precise tracking.
  • Rule 3: Adjustments based on positional errors take precedence over those based on average speed within the time domain of future predictions, prioritizing path tracking accuracy.
Input variable position error e, unit: meters; domain [0, 0.2]; fuzzy subsets designed as NS(Minimal), MS(Small), O(Medium), ML(Large), and NL(Extremely Large). The input variable is the average velocity vavg in the future prediction time domain, measured in m/s, with a domain of [0, 0.2]. The fuzzy subsets are NS(Minimal), MS(Small), O(Medium), ML(Large), and NL(Extremely Large). The output variable is the desired virtual steering ratio α , with a domain of [0.1, 6] and fuzzy subsets NS(Minimal), MS(Small), O(Medium), ML(Large), and NL(Extremely Large). All three variables employ triangular membership functions, whose graphical representations are shown in Figure 5. Based on the rules above, the fuzzy rule table shown in Table 1 can be obtained.
The fuzzy computation process for input and output is well-established and can be referenced in reference [29].

3. Experiments and Results

We evaluate the trajectory tracking performance of the algorithm in this paper on a differential tracked robot through simulation and physical experiments.

3.1. Simulation Experiment

We established the robot’s kinematic model in Python 3.0 and implemented the control algorithm. The robot’s maximum speed in the simulation was set to 0.8 m/s, with a body width of 0.4 m. We configured a semicircular tracking trajectory with a radius of 1.5 m, featuring a time-varying control input that accelerates first, maintains constant speed, and then decelerates.We first compared our approach with an MPC algorithm featuring a fixed virtual steering matrix coefficient, followed by comparisons with traditional MPC and PID algorithms. Given that the performance of tracking controllers is highly dependent on parameter tuning, we carefully adjusted the FVSMPC, the penalty matrix of the MPC, and the proportional, integral, and derivative coefficients of the PID algorithm. Furthermore, we uniformly set the time domain T for the controller-based prediction to 20 and used the ECOS solver as the solution. We evaluated the error between the actual trajectory and the reference trajectory according to reference [30]. Specifically, position error is defined as the Euclidean distance between the actual position p(t) and the reference position p d ( t ) .
e p ( t ) = p ( t ) p d ( t ) 2
Angular error is defined as the difference between the actual yaw angle φ ( t ) and the reference yaw angle φ d ( t ) :
e R ( t ) = φ ( t ) φ d ( t )

3.1.1. Comparison with MPC Algorithms with Fixed Virtual Steering Coefficients

We configured four sets of model predictive controllers with fixed virtual steering coefficients of 0.5, 1, 3, and 6 for comparison with the fuzzy adaptive virtual steering model predictive controller proposed in this paper. Figure 6 shows the trajectory plots, demonstrating that all algorithms gradually converge to the reference trajectory, achieving successful trajectory tracking. Figure 7a illustrates the variation in position error, revealing the gradually converging error from 0.2 to 0. Figure 7b shows the angle error variation. The robot initially exhibited significant angular error in adjusting its head angle toward the reference trajectory. We repeated the experiment 10 times, averaging the results for each run. Table 2 lists the average position error, standard deviation, and convergence time for each algorithm. Figure 8 reveals that the virtual steering coefficient adjusted based on error and velocity conditions, initially decreasing from high to low values. As the robot approached the trajectory, the virtual steering coefficient gradually converged to 1.

3.1.2. Comparison with MPC and PID

The simulation was carried out with an initial lateral error of zero. The tracking results are shown in Figure 9. As seen in the figure, all three algorithms can stably track the desired trajectory. We repeated the experiment 10 times, averaging the results for each run. The average position error, standard deviation, and maximum error are shown in Table 3, with minimal differences between them.
The simulation was carried out with an initial lateral error set to 0.2 m. The tracking results are shown in Figure 10, where all three algorithms demonstrate satisfactory tracking of the reference trajectory. The inset in Figure 10 further magnifies the initial portion of the trajectory, providing a clearer view of the tracking performance during the initial phase. The FVSMPC algorithm exhibits superior trajectory tracking without significant overshoot. Figure 11a shows the evolution of the position error, showing that the error gradually converges from 0.2 to zero, while the PID algorithm does not converge. Figure 11b illustrates the angle error variation. We repeated the experiment 10 times, averaging the results for each run. Table 4 summarizes the average position error, standard deviation, and convergence time for each algorithm.

3.2. Physical Experiments

We conducted experiments using the robot shown in Figure 1, employing the DLIO algorithm [31], which combines LiDAR scanning and IMU data for mapping and localization. All processing occurs in a two-dimensional plane. The literature [31] indicates that this mapping and localization algorithm achieves a cumulative error of 0.03 m on a movement distance of 551.38 m. Given our experimental movement distance of 4.71 m, this implies an even smaller positioning error. Furthermore, by adjusting the localization system parameters, we controlled the positioning error within a small area to less than 0.01 m, meeting the requirements for trajectory tracking control. The electromechanical time constant of the motor is 0.34 ms, which meets the response speed requirements for control commands.
Using the same semicircular trajectory with a 1.5 m radius as in the simulation setup, the speed profile involves initial acceleration, followed by constant velocity, and concludes with deceleration. We implemented the FVSMPC algorithm on the robot and compared it with the standard MPC algorithm. Figure 12 displays the actual test trajectory plots: black represents the reference trajectory, red shows the position results of the FVSMPC algorithm, and green indicates the position results of the standard MPC algorithm. Figure 13a illustrates the variation in the robot position error, while Figure 13b depicts the variation in the robot angle error. The curve trends align with the simulation results. We repeated the experiment 10 times, averaging the results for each run. The average position error of the proposed algorithm is 0.0298, while the conventional MPC achieved an average position error of 0.0317, representing a reduction of 5.99%.
In summary, the experimental results indicate that the FVSMPC algorithm designed in this paper can effectively achieve trajectory tracking control in real-world scenarios, and it outperforms the conventional MPC algorithm in terms of convergence speed, average position error, and stability.

4. Discussion

The discussion covers a comparative analysis of the expected versus actual results, detailed comparisons with other methods, and the practical significance of the improvements achieved.

4.1. Results Comparison

The primary objective of the proposed FVSMPC algorithm is to enhance the trajectory tracking performance of differential tracking robots by introducing an adaptive virtual steering coefficient. This coefficient is designed to dynamically adjust based on real-time positional error and velocity, thereby strengthening the robot’s ability to rapidly correct significant errors while maintaining stability during tracking. The actual results of simulations and physical experiments align closely with these expectations.
In simulations, the FVSMPC algorithm demonstrated superior performance compared to VSMPC in metrics including mean position error, standard deviation, and convergence time. Specifically, Table 2 shows the mean position error reduced to 0.021 m, while fixed virtual steering coefficients of 0.5, 1, 3, and 6 yielded values of 0.023 m, 0.026 m, 0.025 m, and 0.024 m, respectively. This indicates that the adaptability of the virtual steering coefficient improves the accuracy of the tracking. Furthermore, the lower standard deviation and the convergence time further highlight its robustness and reliability.
Comparing FVSMPC with traditional MPC and PID algorithms, Figure 11 illustrates the temporal evolution of the position error and the angle error for the three control algorithms. The figure reveals the following. During the initial phase, the FVSMPC algorithm exhibits a rapid increase in angular error to achieve faster adaptation to the desired trajectory. The position error decreases rapidly in the initial stage and stabilizes approximately after 1.8 s, demonstrating fast convergence speed and a small steady-state error. The angular response of the MPC algorithm is slower than that of FVSMPC, stabilizing after about 2.7 s. The angular error response of the PID algorithm is between that of FVSMPC and MPC. Its position error decreases rapidly initially, but exhibits significant oscillations with large amplitude after approximately 2 s, failing to converge. Table 4 shows the average position error, standard deviation, and convergence time, where the FVSMPC algorithm outperforms the baseline MPC and PID algorithms.
In physical experiments, the FVSMPC algorithm average position error is 0.0298 m, compared to 0.0317 m for traditional MPC. This represents a 5.99% reduction in error, indicating a continued strong performance in the real world. However, some discrepancies remain between the simulation and the experimental results. Specifically, the average position error in the physical experiment (0.0298 m) is slightly higher than that in the simulation (0.021 m). This discrepancy can be attributed to the omission of errors associated with mapping-based localization and slippage of the ground track. These factors were assumed in the simulation, but are present in physical experiments. Future research will address these gaps.
Based on the above analysis, the FVSMPC algorithm demonstrates outstanding performance in trajectory tracking tasks, characterized by high accuracy, fast convergence, and excellent stability.

4.2. Significance of Improvement

The FVSMPC algorithm delivers particularly notable enhancements in practical applications. Although a 6% reduction in the average position error may seem modest, even minor error reductions significantly boost reliability and safety in real-world scenarios such as autonomous navigation in dynamic environments. For example, in applications such as smart agriculture, precise trajectory tracking is critical for efficient operations: error reduction translates to more accurate planting, harvesting, and monitoring. Furthermore, for robots operating in complex environments, the faster convergence and enhanced stability of the FVSMPC algorithm are indispensable. The ability to rapidly adapt to changing conditions while maintaining stable trajectories is critical for tasks such as obstacle avoidance and path following. The reduction in maximum error and standard deviation further bolsters the algorithm’s robustness, enabling it to handle disturbances and uncertainties more reliably. In summary, the proposed FVSMPC algorithm achieves the anticipated performance enhancements. It demonstrates superior tracking accuracy, faster convergence, and improved stability compared to conventional MPC and PID algorithms. These improvements are vital in practical applications, where precise and reliable trajectory tracking is essential for efficient and safe motion.

5. Conclusions

This paper proposed a method called FVSMPC for trajectory tracking control of differential tracked robots. It presents a kinematic model of the robot incorporating a virtual steering coefficient, derives an error model, and linearizes it to transform the problem into a quadratic programming formulation for rapid rolling optimization. This model enables adjustment of the controller’s error response capability by modifying the virtual steering coefficient, thereby avoiding the complexity of multi-parameter tuning. Fuzzy control rules based on position error and average velocity are designed to dynamically adjust the virtual steering coefficient, enhancing the model’s adaptive capability. Simulations and experiments demonstrate the superior performance of the proposed control algorithm over conventional MPC and PID algorithms in convergence time, mean position error, and stability, exhibiting excellent control capabilities. As this study did not account for track slippage, future work will refine the robot model by incorporating slippage rate parameters and external disturbance models to enhance tracking performance during trajectory control.

Author Contributions

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

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The dataset that supports the central findings of this study is directly available in this article. Additional data can be requested from the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest.

Abbreviations

The following abbreviations are used in this manuscript:
MPCModel Predictive Control
VSMPCVirtual Steering Coefficient Model Predictive Control
FVSMPCFuzzy Adaptive Virtual Steering Coefficient Model Predictive Control

References

  1. Bai, G.; Meng, Y.; Liu, L.; Gu, Q.; Huang, J.; Liang, G.; Wang, G.; Liu, L.; Chang, X.; Gan, X. Path Tracking for Car-like Robots Based on Neural Networks with NMPC as Learning Samples. Electronics 2022, 11, 4232. [Google Scholar] [CrossRef]
  2. Ning, B.; Han, Q.-L.; Zuo, Z.; Jin, J.; Zheng, J. Collective Behaviors of Mobile Robots Beyond the Nearest Neighbor Rules with Switching Topology. IEEE Trans. Cybern. 2018, 48, 1577–1590. [Google Scholar] [CrossRef]
  3. Batkovic, I.; Ali, M.; Falcone, P.; Zanon, M. Safe Trajectory Tracking in Uncertain Environments. IEEE Trans. Autom. Control 2023, 68, 4204–4217. [Google Scholar] [CrossRef]
  4. Latip, N.B.A.; Omar, R. Car-like robot path tracker with kinematic constraints. In Proceedings of the 2016 6th IEEE International Conference on Control System, Computing and Engineering (ICCSCE), Penang, Malaysia, 25–27 November 2016; pp. 223–227. [Google Scholar]
  5. Yan, X.; Wang, S.; He, Y.; Ma, A.; Zhao, S. Autonomous Tracked Vehicle Trajectory Tracking Control Based on Disturbance Observation and Sliding Mode Control. Actuators 2025, 14, 51. [Google Scholar] [CrossRef]
  6. Ghaffari, S.; Homaeinezhad, M.R. Autonomous path following by fuzzy adaptive curvature-based point selection algorithm for four-wheel-steering car-like mobile robot. Proc. Inst. Mech. Eng. Part C J. Mech. Eng. Sci. 2018, 232, 2655–2665. [Google Scholar] [CrossRef]
  7. 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]
  8. Zhang, R. An Intelligent Connected Vehicle Path Tracking Control Based on Pure Pursuit Control with Particle Swarm Optimization Algorithm. In Proceedings of the 2024 First International Conference on Software, Systems and Information Technology (SSITCON), Tumkur, India, 18–19 October 2024; pp. 1–5. [Google Scholar]
  9. Chen, W.; Liu, F.; Zhao, H. Trajectory-Tracking Control of Unmanned Vehicles Based on Adaptive Variable Parameter MPC. Appl. Sci. 2024, 14, 7285. [Google Scholar] [CrossRef]
  10. Chen, L.; Qin, Z.; Kong, W.; Chen, X. Lateral control using LQR for intelligent vehicles based on the optimal front-tire lateral force. Qinghua Daxue Xuebao/J. Tsinghua Univ. 2021, 61, 906–912. [Google Scholar]
  11. Yang, Z.; Huang, J.; Yang, D.; Zhong, Z. Design and Optimization of Robust Path Tracking Control for Autonomous Vehicles with Fuzzy Uncertainty. IEEE Trans. Fuzzy Syst. 2022, 30, 1788–1800. [Google Scholar] [CrossRef]
  12. Polyakov, A. Nonlinear Feedback Design for Fixed-Time Stabilization of Linear Control Systems. IEEE Trans. Autom. Control 2012, 57, 2106–2110. [Google Scholar] [CrossRef]
  13. Liu, Y.; He, N.; He, L.; Zhang, Y.; Xi, K.; Zhang, M. Self-Tuning of MPC Controller for Mobile Robot Path Tracking Based on Machine Learning. J. Shanghai Jiaotong Univ. (Sci.) 2022, 29, 1028–1036. [Google Scholar] [CrossRef]
  14. Meng, H.; Zhang, J.; Li, S. Dual-mode robust model predictive control for the tracking control of nonholonomic mobile robot. Int. J. Robust Nonlinear Control 2023, 33, 3627–3639. [Google Scholar] [CrossRef]
  15. Jiang, L.; Xie, Y.; Jiang, Z.; Meng, J.; Li, W. Adaptive model predictive control of mobile robot with local path refitting. In Proceedings of the 2022 IEEE 17th Conference on Industrial Electronics and Applications (ICIEA), Chengdu, China, 16–19 December 2022; pp. 1–6. [Google Scholar]
  16. Wei, J.; Zhu, B. Model predictive control for trajectory-tracking and formation of wheeled mobile robots. Neural Comput. Appl. 2022, 34, 16351–16365. [Google Scholar] [CrossRef]
  17. Li, J.; Sun, J.; Liu, L.; Xu, J. Model predictive control for the tracking of autonomous mobile robot combined with a local path planning. Meas. Control 2021, 54, 1319–1325. [Google Scholar] [CrossRef]
  18. Zheng, W.; Zhu, B. Stochastic Time-Varying Model Predictive Control for Trajectory Tracking of a Wheeled Mobile Robot. Front. Energy Res. 2021, 9, 767597. [Google Scholar] [CrossRef]
  19. Tang, J.; Wu, S.; Lan, B.; Dong, Y.; Jin, Y.; Tian, G.; Zhang, W.A.; Shi, L. GMPC: Geometric Model Predictive Control for Wheeled Mobile Robot Trajectory Tracking. IEEE Robot. Autom. Lett. 2024, 9, 4822–4829. [Google Scholar] [CrossRef]
  20. Kayacan, E.; Ramon, H.; Saeys, W. Robust Trajectory Tracking Error Model-Based Predictive Control for Unmanned Ground Vehicles. IEEE/ASME Trans. Mechatron. 2016, 21, 806–814. [Google Scholar] [CrossRef]
  21. Xu, S.; Peng, H. Design, Analysis, and Experiments of Preview Path Tracking Control for Autonomous Vehicles. IEEE Trans. Intell. Transp. Syst. 2020, 21, 48–58. [Google Scholar] [CrossRef]
  22. Li, X.; Lu, Y. Control of a path following caterpillar robot based on a sliding mode variable structure algorithm. Biosyst. Eng. 2019, 186, 293–306. [Google Scholar] [CrossRef]
  23. You, Y.; Yang, Z.; Zhuo, H.; Sui, Y. Research on ground mobile robot trajectory tracking control based on MPC and ANFIS. Control Eng. Pract. 2024, 152, 106040. [Google Scholar] [CrossRef]
  24. Siregar, A.W.N.; Agustinah, T.; Fatoni, A. Trajectory Tracking using Fuzzy Predictive Control for Nonholonomic Mobile Robot. In Proceedings of the 2025 International Seminar on Intelligent Technology and Its Applications (ISITIA), Surabaya, Indonesia, 23–25 July 2025; pp. 53–58. [Google Scholar]
  25. Meng, J.; Xiao, H.; Jiang, L.; Hu, Z.; Jiang, L.; Jiang, N. Adaptive Model Predictive Control for Mobile Robots with Localization Fluctuation Estimation. Sensors 2023, 23, 2501. [Google Scholar] [CrossRef] [PubMed]
  26. Prakash, N.P.S.; Perreault, T.; Voth, T.; Zhong, Z. Adaptive Model Predictive Control of Wheeled Mobile Robots (Version 1). arXiv 2022, arXiv:2201.00863. [Google Scholar]
  27. Ren, C.; Li, C.; Hu, L.; Li, X.; Ma, S. Adaptive model predictive control for an omnidirectional mobile robot with friction compensation and incremental input constraints. Trans. Inst. Meas. Control 2021, 44, 835–847. [Google Scholar] [CrossRef]
  28. Chen, Z.; Chen, X.; Liu, J.; Cen, L.; Gui, W. Learning model predictive control of nonlinear systems with time-varying parameters using Koopman operator. Appl. Math. Comput. 2024, 470, 128577. [Google Scholar] [CrossRef]
  29. Cai, K.-Y.; Zhang, L. Fuzzy Reasoning as a Control Problem. IEEE Trans. Fuzzy Syst. 2008, 16, 600–614. [Google Scholar] [CrossRef]
  30. Lee, J.M. Introduction to Riemannian Manifolds; Springer: Berlin, Germany, 2019. [Google Scholar]
  31. Chen, K.; Nemiroff, R.; Lopez, B.T. Direct LiDAR-Inertial Odometry: Lightweight LIO with Continuous-Time Motion Correction. In Proceedings of the 2023 IEEE International Conference on Robotics and Automation (ICRA), London, UK, 29 May–2 June 2023; pp. 3983–3989. [Google Scholar]
Figure 1. Differential tracked robot: Crawler.
Figure 1. Differential tracked robot: Crawler.
Actuators 14 00493 g001
Figure 2. Trajectory tracking problem description for classic model predictive control.
Figure 2. Trajectory tracking problem description for classic model predictive control.
Actuators 14 00493 g002
Figure 3. Differential tracked robot kinematic model.
Figure 3. Differential tracked robot kinematic model.
Actuators 14 00493 g003
Figure 4. Tracking control trajectories with different virtual steering coefficient.
Figure 4. Tracking control trajectories with different virtual steering coefficient.
Actuators 14 00493 g004
Figure 5. Fuzzy membership function.
Figure 5. Fuzzy membership function.
Actuators 14 00493 g005
Figure 6. Trajectory compared with MPC method using fixed virtual steering coefficient.
Figure 6. Trajectory compared with MPC method using fixed virtual steering coefficient.
Actuators 14 00493 g006
Figure 7. Comparisons of different virtual steering coefficients: (a) Position error comparison. (b) Yaw angle error comparison.
Figure 7. Comparisons of different virtual steering coefficients: (a) Position error comparison. (b) Yaw angle error comparison.
Actuators 14 00493 g007
Figure 8. Virtual steering coefficient variation graph.
Figure 8. Virtual steering coefficient variation graph.
Actuators 14 00493 g008
Figure 9. Trajectory tracking without initial error: (a) FVSMPC tracking trajectory. (b) MPC tracking trajectory. (c) PID tracking trajectory.
Figure 9. Trajectory tracking without initial error: (a) FVSMPC tracking trajectory. (b) MPC tracking trajectory. (c) PID tracking trajectory.
Actuators 14 00493 g009
Figure 10. FVSMPC, MPC, and PID trajectory tracking comparison, in the case of a large initial error.
Figure 10. FVSMPC, MPC, and PID trajectory tracking comparison, in the case of a large initial error.
Actuators 14 00493 g010
Figure 11. Error comparisons, in the case of a large initial error: (a) Position error comparison. (b) Yaw angle error comparison.
Figure 11. Error comparisons, in the case of a large initial error: (a) Position error comparison. (b) Yaw angle error comparison.
Actuators 14 00493 g011
Figure 12. The tracking trajectory of the prototype experiment.
Figure 12. The tracking trajectory of the prototype experiment.
Actuators 14 00493 g012
Figure 13. Prototype experimental errors: (a) Prototype experimental position error. (b) Prototype experimental yaw angle error.
Figure 13. Prototype experimental errors: (a) Prototype experimental position error. (b) Prototype experimental yaw angle error.
Actuators 14 00493 g013
Table 1. Fuzzy membership rules for virtual steering coefficient α .
Table 1. Fuzzy membership rules for virtual steering coefficient α .
Virtual Steering Coefficient α Position Error e p
NSMSOMLNL
The Average Velocity in the Predicted Time Domain v a v g NSNSMSOMLNL
MSNS0OMLNL
OMSMS0OML
MLNSNSNS0ML
NLNSNSNSOML
Table 2. Comparison with the average position error of the fixed virtual steering coefficient algorithm.
Table 2. Comparison with the average position error of the fixed virtual steering coefficient algorithm.
Error TypeFVSMPCVSMPC- α = 0.5 VSMPC- α = 1 VSMPC- α = 3 VSMPC- α = 6
Average Position Error (m)0.0210.0230.0260.0250.024
Standard Deviation0.0570.0610.0590.0580.058
Convergence Time (s)1.83.12.46.06.8
Table 3. Average position error without initial error.
Table 3. Average position error without initial error.
Error TypeFVSMPCMPCPID
Average Position Error (m)0.00210.00200.0037
Standard Deviation0.00080.00080.0008
Maximum Positional Error (m)0.00980.0100.011
Table 4. Average position error in the case of a large initial error.
Table 4. Average position error in the case of a large initial error.
Error TypeFVSMPCMPCPID
Average Position Error (m)0.0210.0260.061
Standard Deviation0.0570.0610.112
Convergence Time (s)1.82.71
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

Zhang, P.; Xia, X.; Fu, Y.; Sun, J. FVSMPC: Fuzzy Adaptive Virtual Steering Coefficient Model Predictive Control for Differential Tracked Robot Trajectory Tracking. Actuators 2025, 14, 493. https://doi.org/10.3390/act14100493

AMA Style

Zhang P, Xia X, Fu Y, Sun J. FVSMPC: Fuzzy Adaptive Virtual Steering Coefficient Model Predictive Control for Differential Tracked Robot Trajectory Tracking. Actuators. 2025; 14(10):493. https://doi.org/10.3390/act14100493

Chicago/Turabian Style

Zhang, Pu, Xiubo Xia, Yongling Fu, and Jian Sun. 2025. "FVSMPC: Fuzzy Adaptive Virtual Steering Coefficient Model Predictive Control for Differential Tracked Robot Trajectory Tracking" Actuators 14, no. 10: 493. https://doi.org/10.3390/act14100493

APA Style

Zhang, P., Xia, X., Fu, Y., & Sun, J. (2025). FVSMPC: Fuzzy Adaptive Virtual Steering Coefficient Model Predictive Control for Differential Tracked Robot Trajectory Tracking. Actuators, 14(10), 493. https://doi.org/10.3390/act14100493

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