Research on Trajectory Tracking of a Two-Link Robot Based on Hybrid GA-SQP Optimized Feedforward-PID Control

Research Article
Open access

Research on Trajectory Tracking of a Two-Link Robot Based on Hybrid GA-SQP Optimized Feedforward-PID Control

Keyu Wang 1*
  • 1 School of Advanced Manufacturing, Nanchang University, Nanchang Jiangxi 330031, China    
  • *corresponding author 5913122038@email.ncu.edu.cn
ACE Vol.147
ISSN (Print): 2755-273X
ISSN (Online): 2755-2721
ISBN (Print): 978-1-80590-055-9
ISBN (Online): 978-1-80590-056-6

Abstract

The increasing deployment of robotic systems in industrial applications has driven widespread use of two-link robots, valued for their high speed and precision. However, their inherent nonlinear dynamics and strong coupling effects present substantial challenges to achieving high-precision trajectory tracking. To address these issues, this paper proposes a feedforward–PID control strategy optimized using a hybrid Genetic Algorithm–Sequential Quadratic Programming (GA–SQP) approach. The proposed method combines the anticipatory capabilities of feedforward control with the corrective feedback of PID control, enabling automatic and efficient parameter tuning. Simulation results demonstrate that, in comparison to conventional PID control, the proposed approach enhances trajectory tracking accuracy by approximately 39.61%. Specifically, the GA–SQP-optimized controller reduces the Root Mean Square Error (RMSE) to 0.48mm for an Archimedean spiral trajectory, and further to 0.01mm for a Sine-like trajectory, confirming its adaptability across various trajectory profiles. Torque analysis further highlights the complementary interaction between feedforward and PID components, substantiating the method’s effectiveness. These results underscore the proposed strategy’s potential to significantly improve trajectory tracking accuracy and robustness for two-link robots, especially in complex dynamic environments.

Keywords:

Two-Link Robot Trajectory Tracking, Feedforward-PID Control, GA-SQP Hybrid Optimization, Nonlinear Dynamic Systems, Robot Control Parameter Optimization

Wang,K. (2025). Research on Trajectory Tracking of a Two-Link Robot Based on Hybrid GA-SQP Optimized Feedforward-PID Control. Applied and Computational Engineering,147,89-98.
Export citation

1. Introduction

Robotic technology has become a key driver of innovation across various fields, including industrial manufacturing, healthcare, and exploration in extreme environments [1-4]. Among these applications, two-link robots are particularly significant in the industrial sector due to their simple design and large operational workspace. However, despite these advantages, two-link robots are characterized by inherently nonlinear dynamics and strong coupling effects, which present substantial challenges in control system design. The dynamic behavior of these robots is typically governed by second-order nonlinear differential equations, making accurate dynamic modeling and parameter identification essential for the development of reliable control frameworks [5,6].

Proportional–Integral–Derivative (PID) controllers are widely used in industrial applications because of their simplicity and cost-effectiveness [7,8]. However, their limitations become apparent when dealing with strongly coupled nonlinear systems. Comparative studies indicate that while PID control offers a fast response, the integration of state-feedback and feedforward methods results in higher control accuracy. In contrast, standalone approaches, such as Linear Quadratic Regulator (LQR) control, often suffer from significant delays and steady-state errors [9].

Recent advancements in control strategies have led to notable improvements in robotic system performance. For instance, Shah et al. combined Computed Torque Control with PID control to effectively mitigate system nonlinearities [5], while Shao et al. developed a feedforward–PID scheme that reduced joint torque root mean square error (RMSE) by more than 60% compared to conventional methods [6]. In controller optimization, Fani et al. compared Particle Swarm Optimization (PSO), Genetic Algorithms (GA), and the Estimation of Distribution Algorithm (EDA) for tuning fractional-order PID parameters [7]. Other notable innovations include Wu’s Fuzzy Fractional-Order Sliding Mode Control [10] and Darajat’s self-tuning sliding mode strategy [11], both of which improve system robustness and reduce steady-state errors. More recently, nature-inspired optimization methods, such as Golden Jackal Optimization, have been applied to enhance trajectory tracking accuracy and system resilience under varying environmental conditions [12].

To address the limitations of existing approaches, this paper proposes a feedforward-PID control strategy optimized through a GA-SQP hybrid optimization approach. The proposed strategy synergistically integrates the anticipatory nature of feedforward control with the robustness of PID control, enabling automatic parameter tuning and overcoming the constraints of traditional tuning methods. Experimental results validate the effectiveness of the proposed approach in improving trajectory tracking accuracy and enhancing system robustness. The structure of this paper is as follows: Section II presents the dynamic modeling; Section III describes the control system design; Section IV details the parameter optimization strategy and experimental verification; Section V concludes the paper and discusses future research directions.

2. Establishment of the two-link robot model

This study focuses on a planar two-link robotic manipulator operating within a vertical gravitational field. Link 1 (length \( {l_{1}} \) , mass \( {m_{1}} \) ) connects to the fixed base via Joint 1, rotating with angular displacement \( {q_{1}}(t) \) under torque \( {τ_{1}} \) . Link 2 (length \( {l_{2}} \) , mass \( {m_{2}} \) ) connects to Link 1 via Joint 2, rotating with angular displacement \( {q_{2}}(t) \) under torque \( {τ_{2}} \) . The centers of mass are located at the midpoints of each link. The basic physical parameters of the system are summarized in Table 1.

Table 1: Basic parameters of the robot

Link

\( l \) (m)

\( m \) (kg)

\( g \) (m/ \( {s^{2}} \) )

Link1

1.0

10

9.81

Link2

1.0

5

9.81

A schematic diagram of the robot structure is illustrated in Figure 1.

Figure 1: Schematic diagram of the two-link robot model

The dynamic model of the system is derived using the work-energy principle. By constructing the Lagrangian from the total kinetic energy \( T \) and total potential energy \( V \) , and applying the Euler–Lagrange equation, the standard dynamic equation of the system is obtained [13]:

\( M(q)\ddot{q}+C(q,\dot{q})\dot{q}+G(q)=τ \) (1)

Here, \( M(q) \) is the inertia matrix, \( C(q,\dot{q}) \) is the Coriolis matrix, \( G(q) \) is the gravity vector. The explicit forms of these matrices are given as follows:

\( M(q)=[\begin{matrix}(\frac{{m_{1}}}{3}+{m_{2}})l_{1}^{2}+\frac{{m_{2}}l_{2}^{2}}{3}+{m_{2}}{l_{1}}{l_{2}}cos⁡{q_{2}} & \frac{{m_{2}}l_{2}^{2}}{3}+\frac{{m_{2}}{l_{1}}{l_{2}}}{2}cos⁡{q_{2}} \\ \frac{{m_{2}}l_{2}^{2}}{3}+\frac{{m_{2}}{l_{1}}{l_{2}}}{2}cos⁡{q_{2}} & \frac{{m_{2}}l_{2}^{2}}{3} \\ \end{matrix}] \) (2)

\( C(q,\dot{q})=[\begin{matrix}-{m_{2}}{l_{1}}{l_{2}}{\dot{q}_{2}}sin⁡{q_{2}} & -\frac{{m_{2}}{l_{1}}{l_{2}}}{2}{\dot{q}_{2}}sin⁡{q_{2}} \\ \frac{{m_{2}}{l_{1}}{l_{2}}}{2}{\dot{q}_{1}}sin⁡{q_{2}} & 0 \\ \end{matrix}] \) (3)

\( G(q)=[ \begin{array}{c} (\frac{{m_{1}}}{2}+{m_{2}})g{l_{1}}cos⁡{q_{1}}+\frac{{m_{2}}g{l_{2}}}{2}cos⁡({q_{1}}+{q_{2}}) \\ \frac{{m_{2}}q{l_{2}}}{2}cos⁡({q_{1}}+{q_{2}}) \end{array} ] \) (4)

The driving torque matrix is \( τ={[\begin{matrix}{τ_{1}} & {τ_{2}} \\ \end{matrix}]^{T}} \) ,the angular velocity vector is \( \dot{q}={[\begin{matrix}{\dot{q}_{1}} & {\dot{q}_{2}} \\ \end{matrix}]^{T}} \) , and the angular acceleration vector is \( \ddot{q}={[\begin{matrix}{\ddot{q}_{1}} & {\ddot{q}_{2}} \\ \end{matrix}]^{T}} \) .

3. Feedforward-PID control for the two-link robot model

To achieve accurate control of the two-link robotic system, a classical PID controller is first designed. The PID control law is expressed as:

\( {τ_{i}}(t)={K_{p}}{e_{i}}(t)+{K_{i}}\int _{0}^{t} {e_{i}}(τ)dτ+{K_{d}}\frac{d{e_{i}}(t)}{dt} \) (5)

where \( i=1,2 \) denotes the joint number; and \( {K_{p}} \) , \( {K_{i}} \) , \( {K_{d}} \) represent the proportional, integral, and derivative gains, respectively. These gains are tuned to ensure a desirable transient response.

To mitigate noise amplification caused by the ideal derivative term, a first-order filter is introduced, resulting in a modified control law:

\( {{τ_{i}}^{ \prime }}(t)={K_{p}}{e_{i}}(t)+{K_{i}}\int _{0}^{t} {e_{i}}(τ)dτ+{K_{d}}z(t) \) (6)

where the filtered derivative signal \( z(t) \) follows the differential equation:

\( \dot{z}(t)=N[{\dot{e}_{i}}(t)-z(t)] \) (7)

The PID parameters were optimized in Simulink, resulting in the following gains: for Joint 1, \( {K_{p1}}= \) 5516, \( {K_{i1}}= \) 10236, \( {K_{d1}}= \) 602, with a noise filter coefficient \( {N_{1}}= \) 184; for Joint 2, \( {K_{p2}}= \) 7207 \( {K_{i2}}= \) 62592, \( {K_{d2}}= \) 50, and \( {N_{2}}= \) 18014.

To enhance control performance, this paper proposes a composite feedforward-PID control strategy based on the dynamic model of the two-link robot. The control torque is decomposed into two components: the feedforward compensation term \( {τ_{ff}}(t) \) and the filtered PID control term \( {{τ_{i}}^{ \prime }}(t) \) . Based on the dynamic formulation given in Equation (1), the total control torque \( τ \) is designed as:

\( τ={τ_{ff}}(t)+{{τ_{i}}^{ \prime }}(t)=M[{q_{i,d}}(t)]{\ddot{q}_{i,d}}(t)+C[{q_{i,d}}(t),{\dot{q}_{i,d}}(t)]{\dot{q}_{i,d}}(t)+G[{q_{i,d}}(t)]+{{τ_{i}}^{ \prime }}(t) \) (8)

To comprehensively evaluate the control performance, a multi-sine wave signal is designed as the desired joint trajectory [14]. The desired angular position \( {q_{i,d}}(t) \) for joint \( i \) is defined as:

\( {q_{i,d}}(t)=\sum _{k=1}^{4}{A_{ik}}sin({ω_{ik}}t+{ϕ_{ik}}) \) (9)

where \( {A_{ik}} \) , \( {ω_{ik}} \) , and \( {ϕ_{ik}} \) represent the amplitude, angular frequency, and phase shift of the \( k \) -th sine component for joint \( i \) , respectively. Joint 1 employs sine components directly, while Joint 2 initially utilizes cosine components, which are then converted to sine form for uniform representation. The parameters for the excitation signal are listed in Table 2.

Table 2: Parameters for the test signal

\( k \)

\( {A_{1k}} \)

\( {ω_{1k}} \) (rad/s)

\( {ϕ_{1k}} \) (rad)

\( {A_{2k}} \)

\( {ω_{2k}} \) (rad/s)

\( {ϕ_{2k}} \) (rad)

1

0.3

1

\( \frac{π}{8} \)

0.4

1

\( \frac{π}{2} \)

2

0.2

2

\( -\frac{π}{4} \)

0.25

2

\( -\frac{π}{5} \)

3

0.15

3

\( \frac{π}{6} \)

0.15

3

\( \frac{9π}{14} \)

4

0.1

4

\( -\frac{π}{3} \)

0.1

5

\( -\frac{π}{8} \)

The simulation results, shown in Figure 2, quantitatively demonstrate the effectiveness of the proposed control strategy. In particular, the feedforward–PID control substantially improves the tracking performance of Joint 1, reducing the RMSE from \( 6.39×{10^{-3}} \) rad to \( 3.859×{10^{-3}} \) rad, a 39.61% improvement in accuracy. The feedforward compensation effectively suppresses the persistent oscillations observed in the PID-only case for Joint 1, while maintaining comparable tracking performance for Joint 2. These results demonstrate stable and accurate tracking, as well as effective anti-interference capabilities, validating the effectiveness of the feedforward-PID strategy for dynamic tracking in two-link robotic systems.

(a)

(b)

Figure 2: Response under multi-sine trajectory tracking with feedforward–PID control (a) Joint 1: position tracking and error comparison (b) Joint 2: position tracking and error comparison

4. Trajectory tracking based on hybrid GA-SQP optimized feedforward-PID control

4.1. Design of feedforward-PID control method based on hybrid GA-SQP optimization

To evaluate the dynamic performance of the proposed feedforward-PID controller, an Archimedean spiral trajectory is selected as the desired path for the robot’s end effector. The trajectory is discretized to ensure numerical stability during inverse kinematics computation. The resulting desired end-effector positions at each sampling point \( {t_{k}} \) are given by:

\( \begin{cases} \begin{array}{c} {x_{d}}({t_{k}})=\frac{A{t_{k}}}{T}cos(\frac{2πn{t_{k}}}{T}) \\ {y_{d}}({t_{k}})=\frac{A{t_{k}}}{T}sin(\frac{2πn{t_{k}}}{T}) \end{array} \end{cases} \) (10)

where \( A=0.7min({l_{1}}+{l_{2}},1.4) \) , \( n=2 \) , \( T=10s \) , and \( {t_{k}}=k\frac{T}{N} \) (where \( k=0,1,…,N \) ), with \( N \) representing the total number of discretized sampling points.

Using the geometric relationships of a two-link planar manipulator, the forward kinematics equations are given by:

\( \begin{cases} \begin{array}{c} x={l_{1}}cos{q_{1}}+{l_{2}}cos({q_{1}}+{q_{2}}) \\ y={l_{1}}sin{q_{1}}+{l_{2}}sin({q_{1}}+{q_{2}}) \end{array} \end{cases} \) (11)

By applying the negative branch of the inverse kinematics solution for \( {q_{2}} \) , the discrete desired joint angles corresponding to the desired end-effector positions \( ({x_{d}}({t_{k}}),{y_{d}}({t_{k}})) \) are computed as:

\( \begin{cases} \begin{array}{c} {q_{2d}}({t_{k}})=-arccos(\frac{{x_{d}}({t_{k}}{)^{2}}+{y_{d}}({t_{k}}{)^{2}}-l_{1}^{2}-l_{2}^{2}}{2{l_{1}}{l_{2}}}) \\ \begin{array}{c} , \\ {q_{1d}}({t_{k}})=arctan2({y_{d}}({t_{k}}),{x_{d}}({t_{k}}))-arctan2({l_{2}}sin⁡{q_{2d}}({t_{k}}),{l_{1}}+{l_{2}}cos⁡{q_{2d}}({t_{k}})) \end{array} \end{array} \end{cases} \) (12)

Due to the periodicity of inverse trigonometric functions, angle discontinuities may occur at 2π. To address this, an angle unwrapping algorithm is applied to ensure smooth joint angle sequences, \( \lbrace {\widetilde{q}_{id}}({t_{k}})\rbrace \) , as shown in Figure 3. To further suppress numerical noise introduced by finite differences and maintain smoothness across the entire trajectory, cubic spline interpolation is employed [15]. This technique generates smooth, continuous representations of the desired joint trajectories \( {q_{i,d}}(t) \) , angular velocities \( {\dot{q}_{i,d}}(t) \) , and angular accelerations \( {\ddot{q}_{i,d}}(t) \) .

Figure 3: Angle unwrapping flowchart

Under the feedforward-PID control framework, the composite control torque \( {τ^{ \prime }}(t) \) is expressed as:

\( {τ^{ \prime }}(t)={{K_{g}}τ_{ff}}(t)+{τ_{i}}(t) \) (13)

where \( {K_{g}} \) is the feedforward gain matrix. The closed-loop dynamics of the two-link robotic system can be formulated in state-space representation as:

\( \frac{d}{dt}[ \begin{array}{c} {q_{1}} \\ {q_{2}} \\ {\dot{q}_{1}} \\ {\dot{q}_{2}} \\ \int _{0}^{t} {e_{1}}(σ)dσ \\ \int _{0}^{t} {e_{2}}(σ)dσ \end{array} ]=[ \begin{array}{c} {\dot{q}_{1}} \\ {\dot{q}_{2}} \\ {[M(q{)^{-1}}({τ^{ \prime }}-C(q,\dot{q})\dot{q}-G(q))]_{1}} \\ {[M(q{)^{-1}}({τ^{ \prime }}-C(q,\dot{q})\dot{q}-G(q))]_{2}} \\ {e_{1}} \\ {e_{2}} \end{array} ] \) (14)

Solving this system provides the actual joint trajectories \( {q_{1}}(t) \) and \( {q_{2}}(t) \) . These joint positions are then substituted into the forward kinematics equation to compute the actual end-effector trajectory \( (x,y) \) , as defined in Equation (11).

The parameter tuning of the controller is framed as a constrained optimization problem, where the objective is to minimize the tracking error of the end-effector trajectory over the planning horizon. The objective function is defined as:

\( minJ(θ)=\int _{0}^{T}({({x_{d}}(t)-x(t,θ))^{2}}+{({y_{d}}(t)-y(t,θ))^{2}})dt \) (15)

where \( θ=[{K_{p1}},{K_{i1}},{K_{d1}},{K_{p2}},{K_{i2}},{K_{d2}},{K_{g}}] \) represents the vector of control parameters to be optimized. The actual end-effector trajectories \( x(t,θ) \) and \( y(t,θ) \) are derived from the system's nonlinear dynamics as functions of the parameter vector \( θ \) . The optimization problem is constrained only by the lower and upper bounds for each parameter, as summarized in Table 3.

Table 3: Parameter optimization range

Parameter

\( {K_{p1}} \)

\( {K_{i1}} \)

\( {K_{d1}} \)

\( {K_{p2}} \)

\( {K_{i2}} \)

\( {K_{d2}} \)

\( {K_{g}} \)

Lower Bound

2000

0

150

4000

200

150

0

Upper Bound

3000

10

250

5000

300

250

2

Given the nonlinear nature of the objective function \( J(θ) \) and the presence of multiple local minima, a two-stage hybrid optimization strategy is adopted. This strategy combines the global search capability of the Genetic Algorithm (GA) [16] with the local refinement efficiency of the Sequential Quadratic Programming (SQP) algorithm [17]. This hybrid approach effectively mitigates the limitations associated with using a single optimization method. Figure 4 illustrates the overall trajectory tracking process, covering key stages from trajectory design to parameter optimization.

Figure 4: Overall trajectory tracking process

The first stage employs GA to explore the global solution space. A population of 100 individuals is initialized, each represented by a 7-dimensional vector \( θ \) subject to the constraints \( lb≤θ≤ub \) . The evolutionary process proceeds through selection, crossover (with a probability of 0.8), mutation (with a probability of 0.1), and elitism for 200 generations, ultimately producing the best-performing individual \( {θ_{ga}} \) with the corresponding objective value \( J({θ_{ga}}) \) .

In the second stage, the GA result is refined using the SQP algorithm through MATLAB's fmincon function. Starting from \( {θ_{ga}} \) as the initial guess, SQP performs constrained local optimization by iteratively updating \( θ \) based on numerically computed gradients. The maximum number of iterations is set to 200. Upon convergence, the final optimized parameters \( {θ^{*}} \) and the minimized objective value \( J({θ^{*}}) \) are obtained.

4.2. Trajectory tracking performance and control effect analysis

The controller parameters obtained through the GA-SQP hybrid optimization are as follows: For Joint 1, \( {K_{p1}}= \) 2500, \( {K_{i1}}= \) 10, \( {K_{d1}}= \) 200; for Joint 2, \( {K_{p2}}= \) 4363.91, \( {K_{i2}}= \) 249.92, \( {K_{d2}}= \) 200; and the feedforward control gain \( {K_{g}}= \) 1.02.

The end-effector trajectory tracking performance for the Archimedean spiral is shown in Figure 5. As illustrated in Figure 5(a), the actual trajectory closely follows the desired path, with a maximum pointwise error of only 2.74mm. The Root Mean Square Error (RMSE) over the entire trajectory duration is 0.48mm, indicating high tracking precision. To further evaluate the controller's perforamnce, robot configurations were captured at four characteristic time instances: \( T=3.6s \) , \( T=5.0s \) , \( T=8.0s \) , and \( T=10.0s \) . These configurations are overlaid on Figure 5(a), demonstrating consistent adherence to the planned path.

Figure 5(b) shows the tracking error in the Cartesian \( x \) and \( y \) directions. A brief transient adjustment phase occurs at the beginning, followed by stabilized error behavior. The error magnitude exhibits periodic growth, which is positively correlated with the increasing radius of the spiral trajectory. This trend aligns with the expected geometric and dynamic characteristics of the spiral.

(a)

(b)

Figure 5: Archimedean spiral trajectory tracking results (a) desired vs. actual end-effector trajectory with robot snapshots (b) cartesian tracking error in the \( x \) and \( y \) directions

The joint angle tracking performance is detailed in Figure 6. Figure 6(a) displays the tracking results for Joint 1, where the desired angle increases approximately linearly from 90° to 780°. An initial maximum tracking error of approximately 1.2° is observed, which stabilizes to within 0.04° after 0.4 seconds. Similarly, Figure 6(b) illustrates the tracking results for Joint 2, with its desired angle rising from -180° to -122°. The initial maximum error is approximately 0.158°, which stabilizes to within 0.007° after 0.3 seconds. These results confirm that Joint 2 achieves higher tracking precision than Joint 1, consistent with the previously reported end-effector error characteristics.

(a)

(b)

Figure 6: Archimedean spiral joint angle tracking results (a) Joint 1: desired vs. actual angle and tracking error (b) Joint 2: desired vs. actual angle and tracking error

To gain deeper insight into the operational mechanism and advantages of the feedforward–PID control strategy, a detailed analysis of the torque components and control performance was conducted. The results are presented in Figure 7.

(a)

(b)

Figure 7: Feedforward–PID torque component analysis and control performance (a) Joint 1: torque decomposition and tracking error(b) Joint 2: torque decomposition and tracking error

Figures 7(a) and 7(b) illustrate the decomposition of the control torque into feedforward ( \( {τ_{ff}}(t) \) ) and PID feedback ( \( {τ_{i}}(t) \) ) components for Joints 1 and 2, respectively. The feedforward torque rapidly approaches the desired torque profile, reflecting its ability to anticipate the system's dynamic demands. However, due to model uncertainties and external disturbances, perfect tracking with feedforward control alone is not achievable, highlighting its limitations in complex, nonlinear environments.

The PID torque component, although smaller in magnitude, provides essential real-time correction by minimizing the output error through closed-loop feedback. This compensatory role is particularly critical in the presence of time-varying or unforeseen disturbances, demonstrating the complementary nature of the hybrid control scheme.

Figures 7(a) and 7(b) also show the torque tracking error for Joints 1 and 2. After a brief transient phase (approximately 0.3 seconds), the torque error stabilizes at 0.026N·m for Joint 1 and 0.008N·m for Joint 2. These results confirm the synergistic effect of the feedforward–PID structure, where the predictive capability of the feedforward term is reinforced by the precision of PID feedback correction.

To further assess the robustness and generalization capability of the proposed control scheme, a sine-like trajectory tracking experiment was conducted. The controller parameters used were as follows: for Joint 1, \( {K_{p1}}= \) 2477.14, \( {K_{i1}}= \) 9.92, \( {K_{d1}}= \) 200.37; for Joint 2, \( {K_{p2}}= \) 5424.23, \( {K_{i2}}= \) 222.44, \( {K_{d2}}= \) 200.38; and the feedforward control gain \( {K_{g}}= \) 1.00. The results are shown in Figure 8.

As depicted in Figure 8(a), the actual trajectory closely follows the desired path, with a maximum pointwise error of just 0.04mm and an RMSE of 0.01mm over the full trajectory duration. Robot configurations were recorded at four representative time instances: \( T=3.6s \) , \( T=5.0s \) , \( T=8.0s \) , and \( T=10.0s \) . These configurations are overlaid on the plot to demonstrate accurate real-time trajectory execution.

Figure 8(b) presents the Cartesian tracking errors in the x and y directions. The error magnitudes remain consistently low throughout the test, emphasizing the controller's robustness against trajectory variation and its strong adaptability across different motion scenarios.

(a)

(b)

Figure 8: Sine-like trajectory tracking results (a) desired vs. actual end-effector trajectory with robot snapshots (b) cartesian tracking error in the \( x \) and \( y \) directions

5. Conclusion

This study presents a hybrid feedforward–PID control strategy optimized via Genetic Algorithm–Sequential Quadratic Programming (GA–SQP) for high-precision trajectory tracking in a two-link robotic system. By combining the predictive capabilities of feedforward control with the real-time error correction of PID feedback, the proposed method effectively addresses the challenges posed by nonlinear dynamics and strong joint coupling in multi-link manipulators. Experimental results demonstrate the superiority of the proposed approach over traditional PID control. For Joint 1, the root mean square error (RMSE) is reduced by approximately 39.61%. In the Archimedean spiral trajectory tracking task, the optimized controller achieves a maximum point error of just 2.74mm and an RMSE of 0.48mm. Furthermore, in a sine-like trajectory test with dynamic variations, the controller shows even greater precision, with a maximum point error of only 0.04mm and an RMSE of 0.01mm. These results highlight the controller's robustness and adaptability across diverse trajectory profiles. Torque component analysis reveals the complementary roles of the feedforward and PID control terms. The feedforward term approximates the required torque based on dynamic modeling, while the PID feedback compensates for real-time disturbances and model mismatches. This collaboration creates an effective "coarse-to-fine" control structure, overcoming the limitations of standalone PID controllers in nonlinear environments. In conclusion, the GA–SQP optimized feedforward–PID strategy offers an efficient and robust solution for precision trajectory tracking in robotic systems. Future work will explore its adaptability to more complex operational conditions, including varying payloads, external disturbances, and parameter uncertainties. Additionally, the framework will be extended to multi-degree-of-freedom manipulators to provide scalable and reliable control solutions for advanced industrial automation.


References

[1]. Liu, Yixiang, et al. "An In-pipe crawling robot based on tensegrity structures." 2022 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). IEEE, 2022.

[2]. Aole, Sumit, et al. "Active disturbance rejection control based sinusoidal trajectory tracking for an upper limb robotic rehabilitation exoskeleton." Applied Sciences 12.3 (2022): 1287.

[3]. Liu, Fenghua, et al. "Operational stability control of a buried pipeline maintenance robot using an improved PSO-PID controller." Tunnelling and Underground Space Technology 138 (2023): 105178.

[4]. He, Yuetong, et al. "Water Surface Walking of Six-Legged Robot by Controlling Attitude of Feet When It Enter Water." 2023 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). IEEE, 2023.

[5]. Shah, Jolly Atit, and S. S. Rattan. "Dynamic analysis of two link robot manipulator for control design using PID computed torque control." International Journal of Robotics and Automation 5.4 (2016): 277-283.

[6]. Shao, Xingmao, et al. "Research on feedforward control based on robot dynamics parameters identification." 2020 IEEE International Conference on Mechatronics and Automation (ICMA). IEEE, 2020.

[7]. Fani, Davoud, and Elmira Shahraki. "Two-link robot manipulator using fractional order PID controllers optimized by evolutionary algorithms." Biosciences Biotechnology Research Asia 13.1 (2016): 589-598.

[8]. Milind, Joshi Shubangi, et al. "PID control of a double link (2-link) flexible robotic manipulator (2-DOF) in the 3 DE space." 2018 4th International Conference for Convergence in Technology (I2CT). IEEE, 2018.

[9]. Kumari, Riya, et al. "PID, LQR, state feedback, and feed-forward controllers on a two-link robotic manipulator: A simulation-based comparison." 2023 International Conference on Recent Advances in Electrical, Electronics & Digital Healthcare Technologies (REEDCON). IEEE, 2023.

[10]. Wu, Hsiu-Ming. "Joint Position Tracking Control of a Two-Link Planar Robot Arm Using Fuzzy Fractional Order Sliding-Mode Strategy." 2021 21st International Conference on Control, Automation and Systems (ICCAS). IEEE, 2021.

[11]. Darajat, Anisa Ulya, and Swadexi Istiqphara. "Control of two-link robot manipulator with uncertainty parameter using self-tuning sliding mode control." 2020 3rd International Conference on Mechanical, Electronics, Computer, and Industrial Technology (MECnIT). IEEE, 2020.

[12]. Azeez, Muhammad I., and Khaled R. Atia. "Modeling of PID controlled 3DOF robotic manipulator using Lyapunov function for enhancing trajectory tracking and robustness exploiting Golden Jackal algorithm." ISA transactions 145 (2024): 190-204.

[13]. Nguyen-Tuong, Duy, and Jan Peters. "Learning robot dynamics for computed torque control using local Gaussian processes regression." 2008 ECSIS Symposium on Learning and Adaptive Behaviors for Robotic Systems (LAB-RS). IEEE, 2008.

[14]. Schoukens, J., et al. "Survey of excitation signals for FFT based signal analyzers." IEEE Transactions on Instrumentation and Measurement 37.3 (1988): 342-352.

[15]. Seiler, Peter, et al. "Finite horizon robustness analysis of LTV systems using integral quadratic constraints." Automatica 100 (2019): 135-143.

[16]. Conn, Andrew R., et al. "A globally convergent augmented Lagrangian algorithm for optimization with general constraints and simple bounds." SIAM Journal on Numerical Analysis 28.2 (1991): 545-572.

[17]. Nocedal, Jorge, and Stephen J. Wright, eds. Numerical optimization. New York, NY: Springer New York, 1999.


Cite this article

Wang,K. (2025). Research on Trajectory Tracking of a Two-Link Robot Based on Hybrid GA-SQP Optimized Feedforward-PID Control. Applied and Computational Engineering,147,89-98.

Data availability

The datasets used and/or analyzed during the current study will be available from the authors upon reasonable request.

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 EWA Publishing and/or the editor(s). EWA Publishing 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.

About volume

Volume title: Proceedings of the 3rd International Conference on Mechatronics and Smart Systems

ISBN:978-1-80590-055-9(Print) / 978-1-80590-056-6(Online)
Editor:Mian Umer Shafiq
Conference website: https://2025.confmss.org/
Conference date: 16 June 2025
Series: Applied and Computational Engineering
Volume number: Vol.147
ISSN:2755-2721(Print) / 2755-273X(Online)

© 2024 by the author(s). Licensee EWA Publishing, Oxford, UK. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution (CC BY) license. Authors who publish this series agree to the following terms:
1. Authors retain copyright and grant the series right of first publication with the work simultaneously licensed under a Creative Commons Attribution License that allows others to share the work with an acknowledgment of the work's authorship and initial publication in this series.
2. Authors are able to enter into separate, additional contractual arrangements for the non-exclusive distribution of the series's published version of the work (e.g., post it to an institutional repository or publish it in a book), with an acknowledgment of its initial publication in this series.
3. Authors are permitted and encouraged to post their work online (e.g., in institutional repositories or on their website) prior to and during the submission process, as it can lead to productive exchanges, as well as earlier and greater citation of published work (See Open access policy for details).

References

[1]. Liu, Yixiang, et al. "An In-pipe crawling robot based on tensegrity structures." 2022 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). IEEE, 2022.

[2]. Aole, Sumit, et al. "Active disturbance rejection control based sinusoidal trajectory tracking for an upper limb robotic rehabilitation exoskeleton." Applied Sciences 12.3 (2022): 1287.

[3]. Liu, Fenghua, et al. "Operational stability control of a buried pipeline maintenance robot using an improved PSO-PID controller." Tunnelling and Underground Space Technology 138 (2023): 105178.

[4]. He, Yuetong, et al. "Water Surface Walking of Six-Legged Robot by Controlling Attitude of Feet When It Enter Water." 2023 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). IEEE, 2023.

[5]. Shah, Jolly Atit, and S. S. Rattan. "Dynamic analysis of two link robot manipulator for control design using PID computed torque control." International Journal of Robotics and Automation 5.4 (2016): 277-283.

[6]. Shao, Xingmao, et al. "Research on feedforward control based on robot dynamics parameters identification." 2020 IEEE International Conference on Mechatronics and Automation (ICMA). IEEE, 2020.

[7]. Fani, Davoud, and Elmira Shahraki. "Two-link robot manipulator using fractional order PID controllers optimized by evolutionary algorithms." Biosciences Biotechnology Research Asia 13.1 (2016): 589-598.

[8]. Milind, Joshi Shubangi, et al. "PID control of a double link (2-link) flexible robotic manipulator (2-DOF) in the 3 DE space." 2018 4th International Conference for Convergence in Technology (I2CT). IEEE, 2018.

[9]. Kumari, Riya, et al. "PID, LQR, state feedback, and feed-forward controllers on a two-link robotic manipulator: A simulation-based comparison." 2023 International Conference on Recent Advances in Electrical, Electronics & Digital Healthcare Technologies (REEDCON). IEEE, 2023.

[10]. Wu, Hsiu-Ming. "Joint Position Tracking Control of a Two-Link Planar Robot Arm Using Fuzzy Fractional Order Sliding-Mode Strategy." 2021 21st International Conference on Control, Automation and Systems (ICCAS). IEEE, 2021.

[11]. Darajat, Anisa Ulya, and Swadexi Istiqphara. "Control of two-link robot manipulator with uncertainty parameter using self-tuning sliding mode control." 2020 3rd International Conference on Mechanical, Electronics, Computer, and Industrial Technology (MECnIT). IEEE, 2020.

[12]. Azeez, Muhammad I., and Khaled R. Atia. "Modeling of PID controlled 3DOF robotic manipulator using Lyapunov function for enhancing trajectory tracking and robustness exploiting Golden Jackal algorithm." ISA transactions 145 (2024): 190-204.

[13]. Nguyen-Tuong, Duy, and Jan Peters. "Learning robot dynamics for computed torque control using local Gaussian processes regression." 2008 ECSIS Symposium on Learning and Adaptive Behaviors for Robotic Systems (LAB-RS). IEEE, 2008.

[14]. Schoukens, J., et al. "Survey of excitation signals for FFT based signal analyzers." IEEE Transactions on Instrumentation and Measurement 37.3 (1988): 342-352.

[15]. Seiler, Peter, et al. "Finite horizon robustness analysis of LTV systems using integral quadratic constraints." Automatica 100 (2019): 135-143.

[16]. Conn, Andrew R., et al. "A globally convergent augmented Lagrangian algorithm for optimization with general constraints and simple bounds." SIAM Journal on Numerical Analysis 28.2 (1991): 545-572.

[17]. Nocedal, Jorge, and Stephen J. Wright, eds. Numerical optimization. New York, NY: Springer New York, 1999.