Next Article in Journal
Cross-Path Planning of UAV Cluster Low-Altitude Flight Based on Inertial Navigation Combined with GPS Localization
Previous Article in Journal
An Effective Hybrid Sampling Strategy for Single-Split Evaluation of Classifiers
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Support-Vector-Regression-Based Kinematics Solution and Finite-Time Tracking Control Framework for Uncertain Gough–Stewart Platform

School of Intelligent Technology, Shanghai Institute of Technology, Shanghai 201418, China
*
Author to whom correspondence should be addressed.
These authors contributed equally to this work.
Electronics 2025, 14(14), 2872; https://doi.org/10.3390/electronics14142872
Submission received: 18 June 2025 / Revised: 13 July 2025 / Accepted: 15 July 2025 / Published: 18 July 2025

Abstract

This paper addresses the trajectory tracking control problem of a six-degree-of-freedom Gough–Stewart Platform (GSP) by proposing a control strategy that combines a sliding mode (SM) controller with a rapid forward kinematics solution algorithm. The study first develops an efficient forward kinematics method that integrates Support Vector Regression (SVR) with the Levenberg–Marquardt algorithm, effectively resolving issues related to multiple solutions and local optima encountered in traditional iterative approaches. Subsequently, a SM controller based on the GSP’s dynamic model is designed to achieve high-precision trajectory tracking. The proposed control strategy’s robustness and effectiveness are validated through simulation experiments, demonstrating superior performance in the presence of model discrepancies and external disturbances. Comparative analysis with traditional PD controllers and linear SM controllers shows that the proposed method offers significant advantages in both tracking accuracy and control response speed. This research provides a novel solution for high-precision control in GSP applications.

1. Introduction

The Gough–Stewart Platform (GSP) [1,2,3], a six-degree-of-freedom parallel mechanism first introduced in 1965 as a flight simulator, is renowned for its high-speed performance, dynamic stability, and precise repeatability. Its advanced parallel structure has established its indispensability across various applications. In aircraft simulation, it ensures precision and stability. For vibration isolation systems, it provides a critical dynamic response. In surgical robotics, it offers exceptional accuracy, and in high-precision machining, it ensures consistent performance across varying conditions.
The control of parallel mechanisms [1,4,5] like the GSP presents significant challenges, primarily due to the strong coupling and nonlinear characteristics inherent in their control variables. These complexities have made the control of the GSP a central topic of interest within the academic community, driving ongoing research efforts aimed at developing more effective control strategies. One of the fundamental objectives in controlling the GSP is to ensure high-precision tracking of predefined trajectories, a task that becomes particularly challenging when the system is subject to external disturbances. Furthermore, in nonlinear systems with strict-feedback forms, preassigned finite-time control schemes have been developed to guarantee rapid convergence and ensure that all signals of the closed-loop system meet preassigned finite-time stability criteria [6], which could also inform GSP control strategies that demand fast and precise trajectory tracking.
The mainstream control methods for GSP can be categorized into task-space and joint-space control. Task-space control involves using sensors to obtain the end-effector’s position and orientation, followed by feedback control. However, the high cost and spatial requirements of these sensors limit its practical application. In contrast, joint-space control directly adjusts the lengths of the GSP’s six legs to track the desired trajectory. A key challenge in joint-space control is the requirement to rapidly compute the end-effector’s position and orientation from the leg lengths. This forward kinematics computation is essential to ensure that the control system accurately correlates the actuator inputs (leg lengths) with the resulting platform motion, which is necessary to meet real-time demands and maintain precise trajectory tracking.
Solving the forward kinematics of GSP is particularly challenging due to the complex nonlinear coupled equations involved. Researchers have developed various methods including algebraic elimination, interval analysis, and optimization techniques to address this problem. In [7], a 20th-degree univariate polynomial for a general 6-6 Stewart platform was derived using a 15 × 15 Sylvester matrix. Reference [8] proposed a hybrid method combining the immune algorithm, genetic algorithm, and fuzzy system to solve the forward kinematics problem of the Stewart platform, comparing it with the standard genetic algorithm. Reference [9] proposed a method for real-time forward kinematics of Stewart platforms, which involves decomposing the leg space into cells, using inverse kinematics to generate data, and storing model parameters in a lookup table for fast online computation. Similarly, reference [10] proposed an efficient algorithm based on dual quaternions and the Jacobian matrix, converting the problem into a system of quadratic equations and developing a convergent iterative solution. The use of sensor feedback is also a common approach for solving the forward kinematics of parallel platforms. In [11], a method using tetrahedron configurations is proposed to solve the forward kinematics of the 6-6 Stewart platform, avoiding numerical iteration and providing a unique solution, which makes it suitable for real-time applications.
However, iterative methods still have limitations, such as issues with multiple solutions and local optima. To address these challenges, some researchers have recently turned to neural network algorithms to enhance the accuracy of the solutions. In [12], a forward kinematic solution for the Stewart platform was developed by employing a linear estimator based on Luenberger’s observer, alongside a nonlinear estimator utilizing a measurement model. Given the complexity of designing the estimator parameters, a neural network with a multi-layer perceptron architecture was introduced to optimize the estimation gain via backpropagation. The proposed methodology was validated through simulations, demonstrating its robustness and accuracy. In [13], a soft-computing-based approach is introduced to solve the forward kinematics problem of the Stewart platform. A multi-layer feed-forward neural network is trained using different metaheuristic optimizers, including Particle Swarm Optimization (PSO), Modified Chaotic Invasive Weed Optimization (MCIWO), and Teachers’ Learning-Based Optimization (TLBO), with the training dataset generated from the inverse kinematics solution.
Despite these advances, there is still no universally effective method for real-time solutions to the forward kinematics of parallel mechanisms. To further enhance these approaches, this paper proposes a hybrid method that combines SVR with iterative solving. First, the system of nonlinear equations for the forward kinematics is formulated, and data generated via inverse kinematics is used to train the SVR model. The SVR then provides an initial guess for the iterative process, which is refined using the Levenberg–Marquardt method. Compared to neural networks, SVR models are more compact and can produce results faster, making them more suitable for real-time applications.
Accurate and fast forward kinematics solutions are not only essential for determining the platform’s position and orientation but are also crucial for implementing advanced control strategies. Advanced control strategies for the GSP aim to achieve precise trajectory tracking and robust disturbance rejection. Traditional methods [14], such as PID [15] and fuzzy control [16], have been applied with some success, but they often lack the necessary tracking speed and accuracy, keeping GSP control an active research area. In [17], an improved equivalent input disturbance (IEID) method combined with SM control was proposed to enhance trajectory tracking and disturbance rejection. A joint space neural network compensation method was introduced in [18] to address uncertain loads in Stewart robots. A decentralized adaptive synchronized control scheme was presented in [4], which integrates synchronization and model reference adaptive control (MRAC) to ensure tracking accuracy and joint coordination under uncertainties. The method features a simple structure and does not rely on precise dynamic models, making it suitable for real-time control. Additionally, reference [19] integrated a dynamic model of hydraulic cylinders with a SM controller to achieve trajectory tracking in hydraulically actuated GSPs.
Most existing schemes operate in joint space, which limits their effectiveness in handling the nonlinearities and external disturbances inherent to the GSP. To address these challenges, accurate dynamic modeling has become essential. Several approaches have been developed for the dynamic modeling of the GSP, including the principle of virtual work [20], screw theory [21], the Lagrange method [22], and the Newton–Euler method [23]. The results obtained from these methods for solving the dynamic equations of the GSP are generally similar. Current research in this area focuses on improving computation speed and reducing the number of parameters, which is critical for enabling real-time control. In parallel, advanced control strategies, such as direct adaptive finite-time control using neural networks, have been proposed to address additional challenges such as time delays and quantized inputs in strict-feedback nonlinear systems, offering a novel approach to further improve the control performance of systems like the GSP [24].
When addressing external disturbances and ensuring stability in complex systems, the application of sliding mode control (SMC) has proven to be effective. For example, a pre-assigned time sliding mode approach has been proposed for distributed secondary control in microgrids, where a time-varying gain function is used to set the convergence time independently of initial conditions and other design parameters [25]. This ensures that system states, such as frequency and voltage errors, converge to the sliding surface within the pre-assigned time, making it a robust method for managing systems under external disturbances and uncertainties. Building on this concept, recent studies have extended the use of SMC to multi-system synchronization problems, particularly under uncertainties and disturbances. For instance, the finite-time synchronization of uncertain chaotic systems using SMC [26] provides a solid foundation for applying similar control strategies to systems like the Stewart platform, where precise coordination and disturbance rejection are critical. Furthermore, to further enhance the system’s robustness against disturbances, event-triggered control methods have also been successfully employed. A notable example is the improved event-triggered-based anti-disturbance control method proposed for Takagi–Sugeno fuzzy wind-turbine systems [27], which offers valuable insights for optimizing control strategies in systems like the Stewart platform. Additionally, in addressing motion and input constraints in spacecraft operations, a learning-based robust optimal control approach has been proposed, demonstrating how robust control strategies can be applied to systems facing similar challenges as the Stewart platform [28].
SM control [29,30] is considered a robust control technique for complex higher-order nonlinear systems, particularly under the influence of parametric uncertainties [31] and external disturbances. Given its robustness and effectiveness in handling uncertainties, SMC [32] has been widely adopted in various robotic systems. In [17], an integrated control method combining an improved equivalent-input-disturbance (IEID) estimator and sliding-mode control (SMC) [33] is proposed for the Stewart platform, aimed at enhancing reference tracking and disturbance rejection. A state observer and IEID estimator are used to compensate for overall disturbances, while a small sliding-mode gain reduces chattering and ensures tracking precision. The system’s stability is analyzed based on Lyapunov theory, with the observer and estimator gains designed using a linear matrix inequality. The experimental results demonstrate superior disturbance rejection compared to standalone SMC and IEID methods. In [34], a multivariable integral SM controller is proposed for MIMO systems, where the conventional discontinuous feedback control is replaced by a multivariable super twisting algorithm to eliminate chattering while maintaining disturbance rejection. The proposed controller achieves continuous control and demonstrates effectiveness through simulation results. In [35], a fast terminal SM control technique is proposed for robust tracking of a nonlinear mass–spring system with parametric uncertainties and external disturbances. The method uses Lyapunov stability theory [36] and is validated through simulations and experiments. In [37], a novel non-singular terminal SM surface incorporating an arctan function is proposed for trajectory tracking of n-link robotic manipulators. The effectiveness of the approach is demonstrated using a two-link robotic manipulator.
The main contributions of this paper can be divided into three parts:
  • Novel Kinematics Solution Based on SVR: This paper proposes an innovative kinematics solution for Generalized Spatial Mechanisms (GSP) by integrating Support Vector Regression (SVR) with the Levenberg–Marquardt method. Unlike traditional iterative algorithms, this hybrid approach ensures computational accuracy through iteration while leveraging SVR for efficient inference of the initial iterative values. This not only prevents the iteration from getting trapped in local optima but also improves overall computational efficiency. The proposed method accelerates convergence and reduces sensitivity to initial conditions, making it a highly effective alternative for solving complex spatial mechanism problems.
  • Finite-Time Convergent Precise Trajectory Tracking: A significant advancement of this study is the introduction of a finite-time convergent sliding mode control (SMC) strategy, specifically designed for the precise and rapid trajectory tracking of Generalized Spatial Mechanisms (GSP). Compared to traditional SMC methods, the proposed approach guarantees finite-time convergence, ensuring deterministic control performance within a predefined time horizon. Furthermore, in comparison with the widely used PID control method, this approach exhibits smaller tracking errors and faster convergence speed, making it particularly suitable for scenarios that demand high responsiveness and control precision.
  • Enhanced Robustness Against Uncertainties and Disturbances: The proposed control framework explicitly considers model uncertainties and external disturbances, thereby significantly enhancing system robustness. Unlike conventional control schemes, which often suffer from degraded performance under varying conditions, our method ensures sustained precision and stability. Extensive simulations validate the effectiveness of our approach, achieving superior tracking performance and robustness even when subject to unknown disturbances and model mismatches.
This paper is structured into five sections. Section 1 introduces the research background and current state of the GSP. Section 2 outlines the control problems that need to be addressed. In Section 3, a model-based SM controller is proposed, along with a forward kinematics solution method that combines an SVR machine with an iterative algorithm, and the stability of the controller is demonstrated. Section 4 presents the simulation results, including a comparison with PD control, Adaptive PID control, and linear SM control. Finally, Section 5 provides a summary and conclusion of the entire paper.

2. Problem Statement

In this section, we define the basic structure and control problem of the GSP. Figure 1a illustrates a 6-degree-of-freedom Stewart platform. The platform consists of a fixed base, a movable platform, and six identical legs connecting the movable platform to the fixed base. Each linkage is connected to the fixed base and the movable platform through a universal joint at one end and a spherical joint at the other. The length of each linkage can be adjusted via hydraulic or screw-based actuators, allowing the movable platform to achieve effective 6-degree-of-freedom motion.
Define the coordinate system of the fixed platform as the base coordinate system B and the coordinate system fixed to the upper platform as the moving coordinate system T , as shown in Figure 1b. The origins of the two coordinate systems are located at the centroids of the movable and fixed platforms, respectively. At the initial position, the x T y T plane is parallel to the horizontal plane. z T and z are perpendicular to the horizontal plane. The coordinates a i and b i ( i = 1 6 ) represent the position vectors of the upper and lower joints connecting the legs to the fixed and movable platforms, respectively. According to this definition, a i B represents the position vector of the universal joint relative to the B coordinate system, and b i T represents the position vector of the spherical joint relative to the T coordinate system. Therefore, both vectors are constants determined by the configuration. Define the vector P = p x , p y , p z T as the position of the origin of the moving coordinate system T relative to the base coordinate system B . The vector l i represents the linkage vector connecting joints a i and b i , and r i is the length of the linkage.
The dynamics of the Stewart–Gough Platform can be expressed as
A ( r ) r ¨ + B ( r , r ˙ ) r ˙ + C ( r ) = f + τ
where r = r 1 , r 2 , , r 6 T represents the vector of leg lengths, f = f 1 , f 2 , , f 6 T represents the vector of forces applied along the legs, and τ = τ 1 , τ 2 , , τ 6 T represents the vector of forces exerted on the links due to external disturbances. The matrix A ( r ) , a 6 × 6 matrix, represents the inertia matrix, which characterizes the mass distribution and resistance to acceleration within the system. The matrix B ( r , r ˙ ) , also a 6 × 6 matrix, captures the Coriolis and centrifugal forces that arise due to the system’s motion. Lastly, C ( r ) is a 6 × 1 vector representing the gravitational forces acting on the system based on its current configuration.
Considering that there are discrepancies between the established dynamic model and the actual model,
A ( r ) = A 0 ( r ) + Δ A ( r )
B r , r ˙ = B 0 r , r ˙ + Δ B r , r ˙
C r = C 0 r + Δ C r
The matrices A 0 ( r ) , B 0 ( r , r ˙ ) , and C 0 ( r ) represent the parameter matrices obtained through the dynamic model, while Δ A ( r ) , Δ B ( r , r ˙ ) , and Δ C ( r ) represent the uncertainties of the system model. The link tracking error e 1 and its derivative e 2 are defined as follows:
e 1 = r r g
e 2 = d d t e 1 = r ˙ r ˙ g
where r g represents the vector of desired link lengths, and r ˙ g represents the desired velocity, both of which are 6-dimensional vectors. Similarly, r denotes the current actual link lengths, and r ˙ represents the actual link velocities, both also being 6-dimensional vectors. The error between the actual and desired values is denoted by e 1 , which is a 6-dimensional vector, while e 2 represents the time derivative of e 1 and is likewise a 6-dimensional vector. After simplification, we obtain
e 1 ˙ = e 2
e 2 ˙ = G ( e ) + A 0 1 ( r ) f + D ( e , e ˙ )
where e = e 1 T , e 2 T T R 12 . G ( e ) and D ( e , e ˙ ) are given by the following expressions:
G ( e ) = A 0 1 B 0 r ˙ + C 0 r g ¨ D ( e , e ˙ ) = A 0 1 v Δ A r ¨ Δ B r ˙ Δ C

3. Control Development

To ensure that the moving platform follows the desired trajectory, a SM control-based scheme is implemented. In practical applications, measuring the position and orientation of the platform often requires gyroscopes and position sensors. However, these devices not only add to the cost but also take up considerable space, making them unsuitable for certain setups. The lengths of the six legs are easier to measure than the platform’s position and orientation. Thus, the platform’s pose is determined through forward kinematics based on leg lengths, and this information is used for the platform’s dynamic modeling.

3.1. Kinematic Solution of the GSP

In contrast to serial joint robots, parallel mechanisms like the GSP exhibit an inherent structural complexity. These systems are typically characterized by easier access to inverse kinematic solutions as their closed-loop architecture lends itself to more direct calculation of joint variables given the position of the end-effector. However, the forward kinematic problem for such parallel mechanisms is considerably more challenging, often necessitating the formulation and solution of a complex system of nonlinear equations to determine the platform’s pose from the actuator lengths.

3.1.1. Inverse Kinematics of the GSP

The inverse kinematics of the Gough–Stewart platform (GSP) involves computing the leg lengths based on the pose of the moving platform. The platform pose is described by a translation vector P R 3 and a unit quaternion ζ H , which represents its orientation relative to the base frame. Let a i R 3 and b i R 3 denote the coordinates of the i-th leg’s attachment points on the base and the moving platform, respectively.
Using quaternion rotation, the i-th leg vector in the base frame is given by
l i = P + ζ b i ζ a i , i = 1 , , 6
The corresponding leg length is computed as
r i = l i , i = 1 , , 6
This formulation provides a compact and robust means of calculating the leg lengths from the platform pose using quaternion algebra.

3.1.2. Forward Kinematics of the GSP

The forward kinematics of the Gough–Stewart platform aims to determine the pose of the moving platform from the given leg lengths. The pose is represented by a dual quaternion ρ = [ ζ , η ] , where ζ H is a unit quaternion representing rotation, and η = q P ζ encodes translation.
Based on the geometry of the platform, the i-th leg vector in quaternion form satisfies
q l ( i ) = q P + ζ q b ( i ) ζ q a ( i ) , i = 1 , , 6 .
By further manipulation, the squared leg length can be written as
l i 2 = η 2 + b i 2 + a i 2 + 2 ( ζ η ) · q b ( i ) 2 ( η ζ ) · q a ( i ) 2 ( ζ q b ( i ) ζ ) · q a ( i ) .
This expression can be rearranged into a quadratic form with respect to ρ , yielding
f i ( ρ ) = ρ T M i ρ r i 2 = 0 , i = 1 , , 6 ,
along with two additional constraints to ensure ρ is a unit dual quaternion:
f 7 ( ρ ) = 1 2 ρ T M 7 ρ 1 = 0 , f 8 ( ρ ) = 1 2 ρ T M 8 ρ = 0 ,
where the constraint matrices are defined as
M 7 = 2 I 4 × 4 0 4 × 4 0 4 × 4 0 4 × 4 , M 8 = 0 4 × 4 I 4 × 4 I 4 × 4 0 4 × 4 .
This system of eight nonlinear equations is solved using the Levenberg–Marquardt (LM) method, which minimizes the sum of squared residuals:
min ρ F ( ρ ) 2 2 = i = 1 8 f i ( ρ ) 2 ,
with the iterative update given by
ρ k + 1 = ρ k ( J T J + λ I ) 1 J T F ( ρ k ) .
The Levenberg–Marquardt (LM) method is effective for solving nonlinear systems involving quadratic equations. When initialized near the true solution, it can avoid local minima and rapidly converge to a global or near-global solution. Therefore, selecting a good initial value is critical for both accuracy and efficiency.
To provide a better initialization for forward kinematics, a Support Vector Regression (SVR) model is trained using data generated from inverse kinematics.The basic principle of support vector regression (SVR) is illustrated in Figure 2. The input to the model is the vector of six leg lengths q i R 6 , and the output is the platform pose represented as a dual quaternion x i = [ q r , q d ] T R 8 , where q r denotes rotation and q d denotes translation.
SVR learns a nonlinear mapping:
f ( q ) = x
using a kernel-based approach. A radial basis function (RBF) kernel is employed:
K ( q i , q j ) = exp γ q i q j 2
and the regression function takes the following form:
f ( q ) = i = 1 n ( α i α i ) K ( q i , q ) + b
Each of the eight pose components is predicted by an independent SVR model. Compared to neural networks, SVR provides a better trade-off between prediction quality and computational cost. While neural networks may produce initial guesses that are slightly closer to the true solution, SVR achieves significantly faster inference with fewer parameters, making it more suitable for real-time initialization of iterative solvers.

3.2. Controller Design

To begin the controller design process, it is essential to first establish some foundational definitions that will be used throughout the development. These definitions lay the groundwork for understanding the control strategy and its implementation.
Definition 1.
Consider the following autonomous system:
x ˙ = f ( x ) , with f ( 0 ) = 0 , x D , x ( 0 ) = x 0
where the mapping  f : D R n  is a continuous function defined on an open neighborhood  D R n  containing the origin. If, for any  x 0 U , the trajectory  x t , x 0  of the system (22) starting from the initial point  x 0 U { 0 }  is well defined and unique within the time interval  t [ 0 , T ( x 0 ) ) , and satisfies  lim t T ( x 0 ) x ( t , x 0 ) = 0 , then the system (22) is said to be Lyapunov stable and finite-time convergent. If  U = D = R n , the zero solution is referred to as globally finite-time stable.
Lemma 1.
For the system (22), the following conclusions hold:
 1. 
If there exists a  C 1  function  V : D R , a  K  function  α ¯ ( · ) , a real number  ρ > 0 , and  λ ( 0 , 1 ) , such that for an open neighborhood  U D  containing the origin, the following conditions hold:
V ( 0 ) = 0 , α ¯ ( x ) V ( x ) , V ˙ ( x ) ρ V λ ( x ) , x U
the solution of system  x ( t ) = 0  is finite-time stable.
 2. 
If  U = D = R n  and the conditions in Equation (23) are satisfied, then the zero solution  x ( t ) = 0  of system (22) is globally finite-time stable. Moreover, the convergence time  T ( x 0 )  satisfies the following:
T ( x ) 1 ρ ( 1 λ ) V 1 λ ( x ) , x U
Assumption 1.
The lumped disturbance  D ( e , e ˙ )  is bounded and satisfies the following:v
D ( e , e ˙ ) < d 0
For the system in Equation (22), the SM surface can be constructed as follows:
s = α + H e 2 m n
where  e 1 = e 11 , e 12 , , e 16 T  represents the tracking error, and  e 2 = e 21 , e 22 , , e 26 T  is the derivative of the tracking error. The term α is defined as
α = 1 + e 1 1 2 m / n arctan e 11 , , 1 + e 16 2 m / n arctan e 16 T
H is given by
H = diag h 1 , , h 6
where  h i > 0  represents positive real numbers.  m , n  are positive odd integers satisfying  1 < m / n < 2 . By differentiating the sliding surface, we obtain
s ˙ = α ˙ + m n H diag e 21 m n 1 , , e 2 n m n 1 e ˙ 2 = α ˙ + m n Λ G ( e ) + A 0 1 ( r ) f + D ( e , e ˙ )
where  G ( e )  and  D ( e , e ˙ )  are given by Equation (9), and  A 0  represents the inertia matrix from the dynamic equations.
The output force  f  of the legs is composed of two parts:
f = f e + f c
where  f = f 1 , f 2 , , f 6  represents the forces on the six legs. The expressions for  f e  and  f c  are given by the following equations:
f e = A 0 ( r ) ( M + G ( e ) )
f c = A 0 ( r ) d 0 sign ( Λ s ) kA 0 ( r ) s
where the matrix M is given by the following expression:
M = n h 1 m 1 + e 11 2 m n 1 1 + 2 m n e 11 arctan e 11 e 21 2 m n , , n h 6 m 1 + e 16 2 m n 1 1 + 2 m n e 16 arctan e 16 e 26 2 m n T
For a 6-degree-of-freedom Stewart parallel platform, under the control law (30), the trajectory tracking error will converge to zero along the sliding surface (26) within a finite time.

3.3. Stability Proof

To demonstrate that the sliding surface converges in finite time, we construct a Lyapunov function.
V 1 = 1 2 s T s
where the sliding surface s is given by Equation (26). It can be verified that V 1 ( s ) satisfies the conditions V 1 ( 0 ) = 0 and α ¯ ( s ) V 1 ( s ) . A typical choice of the class K function is given by
α ¯ ( s ) = k s 2 , 0 < k < 1 2 .
The first derivative of the Lyapunov function can be obtained as
V ˙ 1 = s T α ˙ + m n H diag e 21 m n 1 , , e 2 n m n 1 e ˙ 2 = s T α ˙ + m n Λ G ( e ) + A 0 1 ( r ) f + D ( e , e ˙ )
Substituting the control law (30) into Equation (36) and simplifying, we obtain
V ˙ 1 = m n s T Λ A 0 1 ( r ) f c + D ( e , e ˙ )
The component f e counteracts the terms G ( e ) and α ˙ in the original equation. Substituting the given expression (32) into the equation yields
V ˙ 1 = m n s T Λ d 0 sign ( Λ s ) + k s + m n s T Λ D ( e , e ˙ ) = m n s T Λ d 0 sign ( Λ s ) m n s T Λ k s + m n s T Λ D ( e , e ˙ )
Because of m n s T Λ k s = k m n i = 1 n h i e 2 i m n 1 s i 2 0 , it can be derived that
V ˙ 1 m n s T Λ d 0 s i g n ( Λ s ) + m n s T Λ D ( e , e ˙ ) m n d 0 Λ s + m n D ( e , e ˙ ) Λ s m n d 0 D ( e , e ˙ ) Λ s η s
where η = m n d 0 D ( e , e ˙ ) min 1 i n | λ i | , and λ i = c i ε 2 i m n 1 , i = 1 , . . . , 6 . According to Lemma 1, the sliding surface (26) converges to zero in finite time.
When the system converges to zero, the system state satisfies the following equation:
s = s 1 , s 2 , , s 6 T = 0
According to (26), we can derive the following equations.
1 + e 1 i 2 m n arctan e 1 i + h i e 2 i m n = 0 , i = 1 , , 6
The above equation can be transformed into
1 + e 1 i 2 arctan e 1 i n m + h i n m e ˙ 1 i = 0
Let ε = arctan e 1 i . Then, Equation (42) can be expressed as
ε n m + h i n m ε ˙ = 0
To prove that the system converges along the sliding surface in finite time, we construct the following Lyapunov function:
V 2 = 1 2 ε 2
It is straightforward to verify that the Lyapunov function V 2 satisfies the conditions specified in Lemma 1, i.e., V 2 ( 0 ) = 0 and α ¯ ( x ) V 2 ( x ) . Differentiate the above equation:
V ˙ 2 = ε ε ˙ = h i n m ε 1 + n m = 2 1 + n m h i n m V 1 + n m / 2 , i = 1 , , 6
Since 1 < m / n < 2 , and ( 1 + n / m ) / 2 ( 3 / 4 , 1 ) , according to Lemma 1, ε converges to zero in finite time along the sliding surface. The convergence time t s i for each rod along the sliding surface s i = 0 satisfies the following:
t s i h i n m 1 n m arctan e 1 i 1 n m h i n m 1 n m π 2 1 n m
The convergence time t s along the sliding surface is defined as the maximum t s i of the convergence times of all the links, that is
t s = max 1 i 6 t s i max 1 i 6 h i n m 1 n m π 2 1 n m
Thus, based on the above derivation, the convergence time of the system along the sliding surface is finite. Since it has been previously proven that the system reaches the sliding surface in finite time, it follows that the proposed control algorithm ensures finite-time convergence within the GSP system.

4. Simulation Results

In this section, we use MATLAB R2020a to simulate the tracking performance of the above control law applied to the GSP. The parameters of the GSP model used are shown in Table 1.
The simulation process is primarily divided into the following four steps:
  • Set the desired motion trajectory of the moving platform and obtain the corresponding joint space trajectory using inverse kinematics.
  • Measure the current lengths and velocities of the legs and use forward kinematics to solve the dynamic model of the moving platform at this time step.
  • Calculate the control forces for the six legs by combining the position and velocity errors with the A matrix in the dynamic model.
  • Substitute the control forces into the dynamic equations and, considering external disturbances, solve for the strut lengths at the next time step using a differential approach. This process then repeats in a new cycle.
Figure 3 provides an overview of the entire simulation process. Additionally, the detailed Kinematics process is depicted in Figure 4, which illustrates the specific procedures and computations required for accurate kinematic analysis.

4.1. Case1: Vertical Lifting

The target motion is set to vertically lift the moving platform, where the desired lengths of the six legs are always equal. In this example, the controller parameters are set as d 0 = 48 , m = 5 , n = 3 , k = 100 , h 1 = h 2 = = h 6 = 0.4 . The parameters of the PD controller are K p = 500 and K d = 10 . All simulation results were obtained under an external disturbance of [ 0 ; 0 ; 10 ] T . The linear SM controller is designed based on the sliding surface s = e 2 + k 1 e 1 , where e 1 represents the position error, and e 2 represents the velocity error. The control law applies a proportional control term to the velocity error and a discontinuous term to enforce the sliding condition. The control force of LSM is given by f = k 2 e 2 k 1 sign ( s ) . The key parameters are selected as follows: the sliding surface parameter k 1 = 300 , the proportional control gain k 2 = 8 , and the switching control gain k 3 = 30 .
The tracking errors and performance for the vertical lifting task, using PD control, linear sliding mode control (LSM), and the proposed controller, are compared in Figure 5. Compared to PD control, the proposed method demonstrates faster convergence and reduced tracking errors. While LSM control exhibits oscillations over an extended period before the tracking error converges to zero, the proposed controller achieves convergence without overshoot or oscillations, and the steady-state error is approximately the same as that of the LSM.
A comparison of velocity tracking performance under various control laws, along with the associated leg output forces, is illustrated in Figure 6. PD control achieves a smoother and more stable tracking response, free from any chattering, albeit with a significantly slower convergence to the desired velocity trajectory. Conversely, both LSM and the proposed method exhibit faster tracking dynamics but at the expense of pronounced chattering. Notably, the proposed method demonstrates a substantial reduction in the amplitude of chattering compared to LSM, offering a superior trade-off between rapid tracking and minimizing high-frequency oscillations.
To mitigate the issue of chattering, the sign function in the controller can be replaced with a saturation function (Sat). The saturation function is defined as
sat ( x , δ ) = 1 x < δ x δ δ x δ 1 x > δ
In this simulation experiment, the parameter δ of the saturation function is set to 1 × 10 6 . Figure 7 presents a comparison of the trajectory tracking error and control forces before and after replacing the sign function with the saturation function. It can be observed that, while the trajectory tracking error remains consistently small, the chattering in the control force is significantly reduced after the system stabilizes, resulting in smoother control behavior.

4.2. Case2: Complex Trajectory Tracking

To further evaluate the tracking performance of the controllers, a more complex trajectory involving simultaneous translational and rotational motion of the moving platform was used. The simulation parameters remained consistent with those of the vertical lifting scenario. As shown in Figure 8, the tracking errors of all six legs under PD, LSM, Adaptive PID, and the proposed method are compared. It can be observed that both LSM and the proposed method achieve significantly smaller tracking errors than the conventional PD controller. The Adaptive PID controller shows slightly improved performance over PD, particularly during periods of rapid trajectory variation, but still falls short of the precision achieved by the sliding-mode-based methods.
To provide a fair comparison, an Adaptive PID (APID) controller was introduced as a benchmark. This controller retains the conventional PID structure but updates its gain parameters online using adaptive laws. The initial values of the proportional, integral, and derivative gains were set to 500, 1, and 20, respectively, for each of the six legs. The learning rates for the adaptive update process were set as γ p = 1000 , γ i = 1000 , and γ d = 500 , applied uniformly across all joints. These settings allow the controller to adjust its parameters in response to changing tracking errors while maintaining a balance between responsiveness and stability.
The tracking responses of the leg lengths under different control strategies—PD, LSM, Adaptive PID, the proposed method, and its saturation-augmented variant—are shown in Figure 9. In regions where the trajectory changes rapidly, the proposed method maintains low tracking errors and superior robustness. In contrast, the Adaptive PID controller exhibits noticeable deviations in such regions, while the LSM method demonstrates improved, yet still less stable, performance compared to the proposed approach.
Table 2 summarizes the average tracking errors and convergence times of four control strategies. The average tracking error is calculated from the final 1 s of the simulation data, using the mean of the last 1000 time steps. The convergence time is defined as the earliest time step at which the tracking error remains continuously below twice the corresponding average error for at least 100 consecutive steps. It can be observed that the Prop SM and LSM controllers achieve significantly lower tracking errors, approximately one order of magnitude smaller than those of the APID and PD controllers. However, they also exhibit slower convergence times. In contrast, the APID and PD methods converge more quickly but maintain higher steady-state errors. This highlights a trade-off between convergence speed and steady-state accuracy across different control strategies.
As illustrated in Figure 10, the velocity tracking performance of links L1 and L4 under different control strategies is compared. The PD controller exhibits relatively large tracking errors, while both the LSM and the proposed method experience chattering due to the use of discontinuous control terms. However, the proposed method shows smaller chattering amplitude compared to LSM. The Adaptive PID controller demonstrates improved tracking accuracy over PD and produces smooth control signals without chattering, but its tracking precision is still lower than that of the sliding-mode-based methods.
Figure 11 illustrates the control forces generated by different control schemes under a complex motion trajectory, where PropSat refers to the proposed method with a saturation function. The results demonstrate that both the PD and Adaptive PID controllers produce relatively smooth control forces but suffer from larger tracking errors and slower convergence rates compared to the sliding-mode-based methods. In contrast, the LSM and the proposed method exhibit chattering due to the discontinuous nature of the control law. However, by replacing the sign function with a saturation function, the amplitude of chattering is significantly reduced, resulting in smoother control responses without sacrificing tracking performance.
Table 3 presents the control effort of each method across all six legs. The proposed method (Prop SM) requires moderate effort, averaging around 187 N2·s per leg. This is higher than that of APID and PD controllers (about 112 N2·s) but significantly lower than the LSM controller, which exceeds 1800 N2·s per leg. This indicates that the proposed method achieves a substantial reduction in tracking error at the cost of slightly increased control effort while remaining far more energy-efficient than conventional sliding mode control.

4.3. Case3: Tracking with Disturbances

An external disturbance is applied at t = 1 s to evaluate controller robustness. The applied force and torque switch from
f ext = 0 0 10 , n ext = 0 0 0
to
f ext = 0 0 100 , n ext = 0 0 10 .
Figure 12 shows the tracking error of the platform under disturbance. Figure 13 presents the actual tracking trajectories. After t = 1 s , both PD and APID controllers experience a significant increase in error, while the proposed sliding mode (Prop SM) controller maintains a consistently low level of error throughout.
Figure 14 illustrates the control force outputs. It can be observed that the Prop SM controller responds rapidly with a sharp change in force at the moment of disturbance, indicating strong disturbance rejection. In contrast, the forces generated by APID and PD do not adjust quickly enough, leading to poor compensation.

4.4. Case4: Efficient Forward Kinematics

In order to investigate efficient solution methods for forward kinematics, we trained a neural network model (NET) and SVR using the same dataset. The neural network consists of two hidden layers, with 15 and 10 nodes, respectively. The activation function used in both hidden layers is tansig, and the output layer uses the purelin activation function.
To compare the advantages of SVR over NET in solving the forward kinematics problem of the GSP, we randomly selected 2000 reachable points. For each point, the initial value for the iterative solution was computed using both SVR and Net. Subsequently, the Levenberg–Marquardt method was employed to iteratively solve for a solution that meets the accuracy requirements. The total computation time for each method is presented in Figure 15.
From the results, it can be concluded that the mean computation time required for generating the initial value using SVR is consistently lower than that of Net. This discrepancy is likely due to the lower computational complexity of SVR compared to Net. Even for a relatively simple neural network structure, its computational overhead is still higher than that of SVR. On the other hand, the time required for the iterative solving process remains similar for both methods. These findings highlight the superiority of SVR in solving the kinematics problem of parallel mechanisms, particularly in terms of computational efficiency.

5. Conclusions

This study proposed an efficient forward kinematics solution algorithm that combines Support Vector Regression (SVR) with the Levenberg–Marquardt method, applied to trajectory tracking control of a six-degree-of-freedom Gough–Stewart platform (GSP). By designing a sliding mode (SM) controller, high-precision trajectory tracking was achieved under complex dynamic conditions. The experimental results show that the proposed method not only improves the speed and accuracy of forward kinematics computation but also significantly enhances the robustness and disturbance rejection capabilities of the controller, especially in the presence of model deviations and external disturbances. In particular, under sudden force and torque disturbances, the SM controller maintained a low tracking error and responded rapidly with effective control force adjustment, while PD and adaptive PID controllers exhibited degraded performance. This work provides a novel approach to addressing the control challenges of GSPs, with promising application prospects. However, it is important to note that, due to constraints in our laboratory conditions, physical experiments were not conducted to validate the proposed method. We sincerely regret this limitation and hope that future studies will provide experimental validation to further substantiate the findings presented herein.
In future work, we aim to focus on several key areas: optimizing the control algorithm to enhance computational efficiency and convergence rates while addressing real-time performance challenges in practical applications. Additionally, efforts will be made to improve the system’s robustness under varying environmental conditions and external disturbances and to expand the system’s scalability for larger platforms. Furthermore, we plan to explore the integration of machine learning techniques for adaptive control. If conditions permit, we are also keen to perform physical experiments to validate the proposed algorithm under real-world conditions, which will provide further insights into its performance and robustness. We believe that such experimental verification will contribute significantly to improving the algorithm’s practical applicability and performance.

Author Contributions

Data curation, W.Y.; formal analysis, W.Y.; methodology, X.J.; project administration, X.J.; resources, W.Y.; software, W.Y.; supervision, X.J.; validation, W.Y.; writing—original draft, W.Y.; writing—review and editing, X.J. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Data Availability Statement

Data are contained within the article.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Duong, T.T.C.; Nguyen, C.C.; Tran, T.D. Experimental Investigation of Motion Control of a Closed-Kinematic Chain Robot Manipulator Using Synchronization Sliding Mode Method with Time Delay Estimation. Appl. Sci. 2025, 15, 5206. [Google Scholar] [CrossRef]
  2. Vu, M.T.; Alattas, K.A.; Bouteraa, Y.; Rahmani, R.; Fekih, A.; Mobayen, S.; Assawinchaichote, W. Optimized Fuzzy Enhanced Robust Control Design for a Stewart Parallel Robot. Mathematics 2022, 10, 1917. [Google Scholar] [CrossRef]
  3. Xie, B.; Dai, S. Robust Terminal Sliding Mode Control on SE(3) for Gough–Stewart Flight Simulator Motion Platform with Payload Uncertainty. Electronics 2022, 11, 814. [Google Scholar] [CrossRef]
  4. Nguyen, T.T.; Nguyen, C.C.; Nguyen, T.M.; Duong, T.T.C.; Ngo, H.T.T.; Sun, L. Decentralized Adaptive Control of Closed-Kinematic Chain Mechanism Manipulators. Machines 2025, 13, 331. [Google Scholar] [CrossRef]
  5. Jing, X.; Li, C. Dynamic Modeling and Solution of 6-DOF Parallel Mechanism. IEEE Access 2022, 10, 33695–33703. [Google Scholar] [CrossRef]
  6. Chen, X.; Zhao, F.; Liu, Y.; Liu, H.; Huang, T.; Qiu, J. Reduced-Order Observer-Based Preassigned Finite-Time Control of Nonlinear Systems and Its Applications. IEEE Trans. Syst. Man Cybern. Syst. 2023, 53, 4205–4215. [Google Scholar] [CrossRef]
  7. Huang, X.; Liao, Q.; Wei, S.; Qiang, X.; Huang, S. Forward Kinematics of the 6-6 Stewart Platform with Planar Base and Platform Using Algebraic Elimination. In Proceedings of the 2007 IEEE International Conference on Automation and Logistics, Jinan, China, 18–21 August 2007; pp. 2655–2659. [Google Scholar] [CrossRef]
  8. Sheng, L.; Wan-long, L.; Yan-chun, D.; Liang, F. Forward kinematics of the Stewart platform using hybrid immune genetic algorithm. In Proceedings of the 2006 International Conference on Mechatronics and Automation, Luoyang, China, 25–28 June 2006; pp. 2330–2335. [Google Scholar] [CrossRef]
  9. Tarokh, M. Real Time Forward Kinematics Solutions for General Stewart Platforms. In Proceedings of the 2007 IEEE International Conference on Robotics and Automation, Rome, Italy, 10–14 April 2007; pp. 901–906. [Google Scholar] [CrossRef]
  10. Yang, X.; Wu, H.; Chen, B.; Li, Y.; Jiang, S. A dual quaternion approach to efficient determination of the maximal singularity-free joint space and workspace of six-DOF parallel robots. Mech. Mach. Theory 2018, 129, 279–292. [Google Scholar] [CrossRef]
  11. Chen, S.H.; Fu, L.C. The Forward Kinematics of the 6-6 Stewart Platform Using Extra Sensors. In Proceedings of the 2006 IEEE International Conference on Systems, Man and Cybernetics, Taipei, Taiwan, 8–11 October 2006; Volume 6, pp. 4671–4676. [Google Scholar] [CrossRef]
  12. Sang, L.H.; Han, M.C. The estimation for forward kinematic solution of Stewart platform using the neural network. In Proceedings of the 1999 IEEE/RSJ International Conference on Intelligent Robots and Systems. Human and Environment Friendly Robots with High Intelligence and Emotional Quotients (Cat. No.99CH36289), Kyongju, Republic of Korea, 17–21 October 1999; Volume 1, pp. 501–506. [Google Scholar] [CrossRef]
  13. Chauhan, D.K.S.; Vundavilli, P.R. Forward kinematics of the Stewart parallel manipulator using machine learning. Int. J. Comput. Methods 2022, 19, 2142009. [Google Scholar] [CrossRef]
  14. Huang, T.; Wang, J.; Pan, H. Adaptive bioinspired preview suspension control with constrained velocity planning for autonomous vehicles. IEEE Trans. Intell. Veh. 2023, 8, 3925–3935. [Google Scholar] [CrossRef]
  15. Sosa-Méndez, D.; Lugo-González, E.; Arias-Montiel, M.; Garcia-Garcia, R.A. ADAMS-MATLAB co-simulation for kinematics, dynamics, and control of the Stewart–Gough platform. Int. J. Adv. Robot. Syst. 2017, 14, 1729881417719824. [Google Scholar] [CrossRef]
  16. Huang, C.I.; Wang, R.S. Hybrid control based on type-2 fuzzy-iterative learning control strategies with stewart platform for repetitive trajectories. In Proceedings of the 2015 10th Asian Control Conference (ASCC), Kota Kinabalu, Malaysia, 31 May–3 June 2015; IEEE: Piscataway, NJ, USA, 2015; pp. 1–5. [Google Scholar]
  17. Zhou, Y.; She, J.; Wang, F.; Iwasaki, M. Disturbance Rejection for Stewart Platform Based on Integration of Equivalent-Input- Disturbance and Sliding-Mode Control Methods. IEEE/ASME Trans. Mechatronics 2023, 28, 2364–2374. [Google Scholar] [CrossRef]
  18. Dai, X.; Song, S.; Xu, W.; Huang, Z.; Gong, D. Modal space neural network compensation control for Gough-Stewart robot with uncertain load. Neurocomputing 2021, 449, 245–257. [Google Scholar] [CrossRef]
  19. Lafmejani, A.S.; Masouleh, M.T.; Kalhor, A. Trajectory tracking control of a pneumatically actuated 6-DOF Gough–Stewart parallel robot using Backstepping-Sliding Mode controller and geometry-based quasi forward kinematic method. Robot. Comput.-Integr. Manuf. 2018, 54, 96–114. [Google Scholar] [CrossRef]
  20. Kalani, H.; Rezaei, A.; Akbarzadeh, A. Improved general solution for the dynamic modeling of Gough–Stewart platform based on principle of virtual work. Nonlinear Dyn. 2016, 83, 2393–2418. [Google Scholar] [CrossRef]
  21. Gallardo, J.; Rico, J.; Frisoli, A.; Checcacci, D.; Bergamasco, M. Dynamics of parallel manipulators by means of screw theory. Mech. Mach. Theory 2003, 38, 1113–1131. [Google Scholar] [CrossRef]
  22. Liu, M.J.; Li, C.X.; Li, C.N. Dynamics analysis of the Gough-Stewart platform manipulator. IEEE Trans. Robot. Autom. 2000, 16, 94–98. [Google Scholar] [CrossRef]
  23. Khalil, W.; Guegan, S. Inverse and direct dynamic modeling of Gough-Stewart robots. IEEE Trans. Robot. 2004, 20, 754–761. [Google Scholar] [CrossRef]
  24. Liu, Y.; Liu, X.; Jing, Y.; Chen, X.; Qiu, J. Direct adaptive preassigned finite-time control with time-delay and quantized input using neural network. IEEE Trans. Neural Netw. Learn. Syst. 2019, 31, 1222–1231. [Google Scholar] [CrossRef]
  25. Chen, X.; Hu, S.; Xie, X.; Qiu, J. Consensus-Based Distributed Secondary Control of Microgrids: A Pre-Assigned Time Sliding Mode Approach. IEEE/CAA J. Autom. Sin. 2024, 11, 2525–2527. [Google Scholar] [CrossRef]
  26. Chen, X.; Huang, T.; Cao, J.; Park, J.H.; Qiu, J. Finite-time multi-switching sliding mode synchronisation for multiple uncertain complex chaotic systems with network transmission mode. IET Control. Theory Appl. 2019, 13, 1246–1257. [Google Scholar] [CrossRef]
  27. Gu, Y.; Shen, M.; Park, J.H.; Wang, Q.G.; Zhu, Z.H. Dynamic Guaranteed Cost Event-Triggered-Based Anti-Disturbance Control of T-S Fuzzy Wind-Turbine Systems Subject to External Disturbances. IEEE Trans. Fuzzy Syst. 2024, 32, 7063–7072. [Google Scholar] [CrossRef]
  28. Tian, Y.; Shi, Y.; Shao, X.; Hu, Q.; Yang, H.; Zhu, Z.H. Spacecraft Proximity Operations Under Motion and Input Constraints: A Learning-Based Robust Optimal Control Approach. IEEE Trans. Aerosp. Electron. Syst. 2024, 60, 7838–7852. [Google Scholar] [CrossRef]
  29. Zhou, W.; Cheng, H.; Chen, Z.; Hua, M. Adaptive Sliding Mode Fault-Tolerant Tracking Control for Underactuated Unmanned Surface Vehicles. J. Mar. Sci. Eng. 2025, 13, 712. [Google Scholar] [CrossRef]
  30. Ahn, H.; Kim, S.; Park, J.; Chung, Y.; Hu, M.; You, K. Adaptive Quick Sliding Mode Reaching Law and Disturbance Observer for Robust PMSM Control Systems. Actuators 2024, 13, 136. [Google Scholar] [CrossRef]
  31. Huang, T.; Pan, H.; Sun, W.; Gao, H. Sine resistance network-based motion planning approach for autonomous electric vehicles in dynamic environments. IEEE Trans. Transp. Electrif. 2022, 8, 2862–2873. [Google Scholar] [CrossRef]
  32. Keshavan, J.; Belgaonkar, S.; Murali, S. Adaptive Control of a Constrained First Order Sliding Mode for Visual Formation Convergence Applications. IEEE Access 2023, 11, 112263–112275. [Google Scholar] [CrossRef]
  33. Huang, T.; Wang, J.; Pan, H.; Sun, W. Finite-time fault-tolerant integrated motion control for autonomous vehicles with prescribed performance. IEEE Trans. Transp. Electrif. 2022, 9, 4255–4265. [Google Scholar] [CrossRef]
  34. Kamal, S.; Chalanga, A.; Bandyopadhyay, B. Multivariable continuous integral sliding mode control. In Proceedings of the 2015 International Workshop on Recent Advances in Sliding Modes (RASM), Istanbul, Turkey, 9–11 April 2015; IEEE: Piscatway, NJ, USA, 2015; pp. 1–5. [Google Scholar]
  35. Amirkhani, S.; Mobayen, S.; Iliaee, N.; Boubaker, O.; Hosseinnia, S.H. Fast terminal sliding mode tracking control of nonlinear uncertain mass–spring system with experimental verifications. Int. J. Adv. Robot. Syst. 2019, 16, 1729881419828176. [Google Scholar] [CrossRef]
  36. Huang, T.; Wang, J.; Pan, H. Approximation-Free Prespecified Time Bionic Reliable Control for Vehicle Suspension. IEEE Trans. Autom. Sci. Eng. 2024, 21, 5333–5343. [Google Scholar] [CrossRef]
  37. Zhai, J.; Xu, G. A novel non-singular terminal sliding mode trajectory tracking control for robotic manipulators. IEEE Trans. Circuits Syst. II Express Briefs 2020, 68, 391–395. [Google Scholar] [CrossRef]
Figure 1. (a) The structure of the GSP. (b) The closed-loop vectors of the Stewart platform.
Figure 1. (a) The structure of the GSP. (b) The closed-loop vectors of the Stewart platform.
Electronics 14 02872 g001
Figure 2. Illustration of SVR.
Figure 2. Illustration of SVR.
Electronics 14 02872 g002
Figure 3. Overall framework.
Figure 3. Overall framework.
Electronics 14 02872 g003
Figure 4. Kinematics process.
Figure 4. Kinematics process.
Electronics 14 02872 g004
Figure 5. (a) Comparison of tracking errors. (b) Comparison of tracking performance.
Figure 5. (a) Comparison of tracking errors. (b) Comparison of tracking performance.
Electronics 14 02872 g005
Figure 6. (a) Comparison of velocity errors. (b) Comparison of control forces.
Figure 6. (a) Comparison of velocity errors. (b) Comparison of control forces.
Electronics 14 02872 g006
Figure 7. (a) Error comparison of sat and sign function. (b) Control force of sat and sign function.
Figure 7. (a) Error comparison of sat and sign function. (b) Control force of sat and sign function.
Electronics 14 02872 g007
Figure 8. Tracking error of the link 1.
Figure 8. Tracking error of the link 1.
Electronics 14 02872 g008
Figure 9. Tracking performance of the six legs.
Figure 9. Tracking performance of the six legs.
Electronics 14 02872 g009
Figure 10. Velocity tracking performance of L1 and L4.
Figure 10. Velocity tracking performance of L1 and L4.
Electronics 14 02872 g010
Figure 11. Force of 6 Legs.
Figure 11. Force of 6 Legs.
Electronics 14 02872 g011
Figure 12. Tracking error of the Stewart platform under external disturbances.
Figure 12. Tracking error of the Stewart platform under external disturbances.
Electronics 14 02872 g012
Figure 13. Tracking trajectories of the Stewart platform under disturbances.
Figure 13. Tracking trajectories of the Stewart platform under disturbances.
Electronics 14 02872 g013
Figure 14. Control force response of each controller under disturbances.
Figure 14. Control force response of each controller under disturbances.
Electronics 14 02872 g014
Figure 15. Solving time using NET and SVR.
Figure 15. Solving time using NET and SVR.
Electronics 14 02872 g015
Table 1. Parameters of the Gough–Stewart Platform.
Table 1. Parameters of the Gough–Stewart Platform.
Position vectors of U-joints and S-joints
b 1 T = [0.0868, 0.4924, 0]T a 1 B = [0.7818, 0.6235, 0]T
b 2 T = [−0.0868, 0.4924, 0]T a 2 B = [−0.7818, 0.6235, 0]T
b 3 T = [−0.4698, −0.1710, 0]T a 3 B = [−0.9309, 0.3654, 0]T
b 4 T = [−0.3830, −0.3214, 0]T a 4 B = [−0.1490, −0.9888, 0]T
b 5 T = [0.3830, −0.3214, 0]T a 5 B = [0.1490, −0.9888, 0]T
b 6 T = [0.4698, −0.1710, 0]T a 6 B = [0.9309, 0.3654, 0]T
Center of mass of the upper and lower sections of each link
c1 = 0.5c2 = 0.5
Mass of the moving platform and each link section
m = 1.5 kgm1 = 0.1 kg, m2 = 0.1 kg
Inertia matrices
I c T = 0.08 0 0 0 0.08 0 0 0 0.08
I i 1 F i = 0.00625 0 0 0 0.00625 0 0 0 0
I i 2 F i = 0.00625 0 0 0 0.00625 0 0 0 0
Table 2. Average tracking error and convergence time of each method.
Table 2. Average tracking error and convergence time of each method.
MethodLink 1Link 2Link 3Link 4Link 5Link 6
Average Tracking Error
APID0.01050.01000.01120.00990.00960.0114
PD0.01050.00980.01220.00920.00860.0125
Prop SM9.89 × 10−49.33 × 10−41.06 × 10−38.84 × 10−41.07 × 10−37.87 × 10−4
LSM7.70 × 10−48.03 × 10−47.17 × 10−47.69 × 10−47.41 × 10−47.26 × 10−4
Convergence Time (time step = 1 ms)
APID636461665954
PD10110753636044
Prop SM198191186139166325
LSM490264608485566513
Table 3. Control effort energy of each method (joules).
Table 3. Control effort energy of each method (joules).
MethodLeg 1Leg 2Leg 3Leg 4Leg 5Leg 6
APID157.83164.24105.0970.8168.54104.82
PD157.05163.37104.2570.6268.10103.77
Prop SM180.68182.88186.74195.37195.14185.32
LSM1.81 × 1031.81 × 1031.83 × 1031.84 × 1031.85 × 1031.83 × 103
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

Jing, X.; Yu, W. Support-Vector-Regression-Based Kinematics Solution and Finite-Time Tracking Control Framework for Uncertain Gough–Stewart Platform. Electronics 2025, 14, 2872. https://doi.org/10.3390/electronics14142872

AMA Style

Jing X, Yu W. Support-Vector-Regression-Based Kinematics Solution and Finite-Time Tracking Control Framework for Uncertain Gough–Stewart Platform. Electronics. 2025; 14(14):2872. https://doi.org/10.3390/electronics14142872

Chicago/Turabian Style

Jing, Xuedong, and Wenjia Yu. 2025. "Support-Vector-Regression-Based Kinematics Solution and Finite-Time Tracking Control Framework for Uncertain Gough–Stewart Platform" Electronics 14, no. 14: 2872. https://doi.org/10.3390/electronics14142872

APA Style

Jing, X., & Yu, W. (2025). Support-Vector-Regression-Based Kinematics Solution and Finite-Time Tracking Control Framework for Uncertain Gough–Stewart Platform. Electronics, 14(14), 2872. https://doi.org/10.3390/electronics14142872

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