Dynamics Analysis and Control of a Two-Link Manipulator
ALY M. EISSA1, MOHAMED FAWZY EL-KHATIB1, MOHAMED I. ABU EL-SEBAH2
1Department of Mechatronics and Robotics Engineering,
Faculty of Engineering,
Egyptian Russian University,
Cairo 11829,
EGYPT
2Department of Power Electronics and Energy Conversion,
Electronics Research Institute,
Cairo 11843,
EGYPT
Abstract: - This article develops a p racticable, efficient, and robust PID controller for the traditional double
pendulum system. Utilizing the Lagrangian method, the equations of motion for the two-link robot manipulator
are initially derived. The system of ordinary differential equations for this nonlinearity describes these
equations. As closed-form solutions for the equations of motion are absent, we approximate the solution of the
initial-value problem. Securing precise user-defined positions while controlling the motion of the two-link
robot manipulator proves to be a formidable challenge due to its non-linear behavior. The primary objective is
to achieve the intended position of the robot manipulator by implementing the computed torque control method.
Once the equation of motion has been derived, MATLAB is utilized to represent the control simulation. Several
computational simulations are employed to validate the controller performance. Specifically, we implement a
PID controller to simulate the balancing of the two links on a mobile robot at any given angle, including
inverted.
Key-Words: - Two-link robot manipulator, Robotics, PID controller, Dynamic control, Trajectory control,
Simulation.
Received: February 22, 2023. Revised: November 21, 2023. Accepted: December 5, 2023. Published: December 31, 2023.
1 Introduction
Robotics is essentially the discipline that
encompasses the examination, creation, and
utilization of robotic systems in the context of
production. They are utilized for various purposes,
including rapidity, precision, and the ability to be
replicated, [1], [2]. Robotics has a wide range of
applications in several industries, including
manufacturing, where it is utilized for tasks such as
pick and place, assembling, drilling, welding,
machine tool load and unload activities, painting,
spraying, and more. These functions are typically
performed in dynamic and noisy environments.
These different tasks have led to the development of
numerous configurations of robotic arms, such as
rectangular, spherical, cylindrical, revolute and
prismatic jointed arms, [3], [4], [5]. This paper
presents a recommended control model to address
the problem at hand. The double pendulum system
is widely used as a model to study nonlinear
dynamics because it exhibits a wide range of
complex and intricate dynamical phenomena. The
robot is a straightforward dynamical model that
displays intricate phenomena such as chaos. This
object comprises two-point masses located at the
endpoints of lightweight rods. The combination of
each mass and the rod constitutes a conventional
and fundamental pendulum. The connection
between the two pendulas allows unrestricted
oscillation within a plane. The proposed robot with
two-link has two degrees of freedom. They are
beneficial as they carry out the functions of human
arms. Once the motion of the two-link manipulator
is defined, we may begin to understand the complex
motion of human arms, [6], [7], [8].
The Lagrangian is formed by the summation of
the overall potential and kinetic energy of the two-
link system. The torques exerted on each link were
calculated using the Euler-Lagrange equations, [9],
[10], [11], [12]. The implementation of the PID
controller aims to replicate the system response to
applied torques, [13]. PID controllers are
WSEAS TRANSACTIONS on SYSTEMS and CONTROL
DOI: 10.37394/23203.2023.18.52
Aly M. Eissa, Mohamed Fawzy El-Khatib,
Mohamed I. Abu El-Sebah
E-ISSN: 2224-2856
487
Volume 18, 2023
extensively utilized because of their
straightforwardness and versatility. Due to their
versatility and uncomplicated nature in both
hardware and simulation systems. PID controllers
continue to be widely used in business and research
due to their versatility, simplicity, flexibility, and
user-friendly nature in both simulation and
hardware systems, [14], [15].
Specialized control systems are often necessary
to effectively operate the two-link manipulator due
to its non-linear nature. Sliding mode control has
been determined to be superior to PID based on the
findings of researchers [8]. Some individuals have
employed Holographic Neural Networks within
their PID feedback loop to execute the action of
folding paper. PID control is designed and utilized
to precisely manipulate a system at specific angles.
Additionally, we present visual representations of
the system's results following the implementation of
PID control, [16], [17], [18], [19].
This work proposes the utilization of a double
pendulum robot using a PID controller. On the
basis of the Lagrangian, the equations of motion for
a two-link robot manipulator are formulated. The
equation of motion for the two-link robot is
represented by a non-linear differential equation.
We must employ a n umerical solution because
there are no closed-form solutions accessible.
MATLAB is used to represent the control
simulation after the equation of motion has been
derived. The conventional two-link manipulator
problem is expanded to include a multiple-link
inverted pendulum supported by a moving object.
In this case, we aim to incorporate the control
system into the portable computer robot.
The present paper is structured as follows, the
equations of motion are derived in section II using
the Lagrangian approach. In addition, we provide
instructions for acquiring the numerical solution
utilizing MATLAB to solve the system differential
equations numerically. We shall elucidate the
configuration of the PID controller for the double
pendulum system. We provide multiple numerical
examples to evaluate the performance of the PID
controller. Ultimately, we present a set of
conclusions.
2 The Model of 2-DOF Robot Arm
2.1 Specifications of the Robot
Figure 1 illustrates a robot arm with two degrees of
freedom. The arm is mostly composed of two links,
each having distinct specifications in the OXY
coordinates.
1 = 1 m represents the initial link's length.
2 = 1 m represents the second link's length.
1 = 1 kg represents the first link's mass.
2 = 1 kg represents the second link's mass.
1 = represents the first link's rotation angel.
2 = represents the second link's rotation angel.
Fig. 1: The 2-DOF robot arm
2.2 Forward Kinematics
The robot forward kinematics is controlled by a set
of factors known as the Denavit-Hartenberg (DH)
table (Table 1), which are used to calculate the
homogeneous transformation matrices relating the
various frames assigned to the structure of the robot.
The following are the DH factors:
Table 1. DH-parameters of the robot, [2]
The following is the derivation of the
homogenous transformation matrices illustrated in
Figure 1:
1
0=11 0 11
11 011
0
0
0
0
1 0
0 1 (1)
2
1=22 0 22
22 022
0
0
0
0
1 0
0 1 (2)
Using Equations (1) and (2), one can derive the
homogenous transformation matrix
2
0 in the
subsequent manner:
Therefore,
(3)
WSEAS TRANSACTIONS on SYSTEMS and CONTROL
DOI: 10.37394/23203.2023.18.52
Aly M. Eissa, Mohamed Fawzy El-Khatib,
Mohamed I. Abu El-Sebah
E-ISSN: 2224-2856
488
Volume 18, 2023
=
0
0
0 1 (4)
2
0=
(5)
The position coordinates of the manipulator
end-effector can be derived from Equation (5) as
follows: =1 cos(1)+ 2 cos(1+2) (6)
=1 sin(1)+ 2 sin(1+2) (7)
Equation (3) defines the orientation matrix of
the final effector as the first three rows and three
columns of the transformation matrix.
7B2.3 Inverse Kinematics
The inverse kinematics of a robotic arm refers to the
process of determining the joint variables of the arm
based on the provided Cartesian coordinates of the
end-effector's position. The equations used to
explain the inverse kinematics problem can be
generated through algebraic or geometric means.
The geometrical technique is regarded as more
straightforward for robot arms with many DOF. We
utilized the geometrical method to explain the
inverse kinematics equations for the 2 robotic arm
seen in Figure 2 in our particular case.
Fig. 2: Inverse Kinematic of the Robot
By applying the Pythagorean theorem, it is
possible to create a mathematical equation for
determining the angle 2 of the elbow joint, as
shown in Figure 2.
2+2=12+22+ 2122 (8)
2=1
2122+21222 (9)
2= ±12
2 (10)
Therefore, 2= ±2
2
(11)
For the joint variable 1:
= ( 1+2 cos 2) cos 1 - 2 sin 1sin 2 (12)
= 2 sin 2 cos 1+ ( 1+2 cos 2) sin 1 (13)
= 1+2 cos 22 sin 2
2 sin 21+2 cos 2 (14)
2+2= ( 1+2 cos 2)2+ (2 sin 2)2 (15)
 sin 1= 1+2 cos 2
2 sin 2 (16)
 cos 1=2 sin 2
1+2 cos 2 (17)
sin 1= sin 1

=( 1+2 cos 2) 2 sin 2
2+2 (18)
cos 1= cos 1

=( 1+2 cos 2) +2 sin 2
2+2 (19)
1=  1
 1
= ( 1+2 cos 2) ±2 sin 2
( 1+2 cos 2) ±2 sin 2 (20)
8B2.4 Robot Dynamics
The dynamic model of a robot establishes a precise
mathematical correlation between the positions of
the robot's joint variables and the dimensional
characteristics of the robot. This pertains to the
motion and exertion of forces in the robotic arm.
The dynamics equations of a robot arm can be
solved using the Euler-Lagrange and Newton-Euler
methods. This study utilized the Euler-Lagrange
approach, which involves computing the combined
kinetic and potential energies to determine the
Lagrangian (L) of the entire system. This
Lagrangian is then used to compute the force or
torque exerted on the joints, as follows:
=
󰇣
󰇗󰇤
 (21)
where the variable F denotes the external force
exerted on the generalized coordinate, while the
torque L applied. The Lagrangian equation of
WSEAS TRANSACTIONS on SYSTEMS and CONTROL
DOI: 10.37394/23203.2023.18.52
Aly M. Eissa, Mohamed Fawzy El-Khatib,
Mohamed I. Abu El-Sebah
E-ISSN: 2224-2856
489
Volume 18, 2023
motion is denoted by L and may be found in
Equation (22).
(),󰇗()=(),󰇗()() (22)
In order to solve the Lagrangian Equation (22),
it is necessary to first compute the kinetic energy
and potential energy as follows:
=1
2 m󰇗2
=
Velocity is calculated by differentiating the
position with time. The position at the end of the
link is determined using well-known factors that are
already known.
1=1 cos 1
1=1 sin 1
2=1 cos(1)+ 2cos(1+2) (23)
2=1 sin(1)+ 2 sin(1+2)
Next, replace the variables in the kinetic energy
equation:
=1
2 11
󰇗2+1
2 11
󰇗2+1
2 22
󰇗2+1
2 22
󰇗2
(24)
=1
2 ( 1+ 2)121
󰇗2+ 1
2 2 121
󰇗2+
2221
󰇗2
󰇗+1
2 2222
󰇗2 + 2 1 2 cos 2 󰇡1
󰇗2
󰇗+
1
󰇗2 (25)
The potential energy equation is defined as:
= 1 1cos 1+ 2(1 cos 1
+2 cos (1
+2)) (26)
By substituting equations (25) and (26) into
equation (21), we may get the Lagrangian equation
as follows:
=1
2 ( 1+ 2)121
󰇗2+ 1
2 2 121
󰇗2+
2221
󰇗2
󰇗+1
2 2222
󰇗2 + 2 1 2 cos 2 (1
󰇗2
󰇗+
1
󰇗2) 1 1cos 1 2(1 cos 1+2 cos (1+
2)) (27)
To determine the force exerted on the robot, we
establish the Lagrange-Euler equation (21) using the
Lagrangian (L).
1,2 =
󰇩
1,2
󰇗󰇪
1,2
The force exerted at joint 1 is determined by
1=(( 1+ 2)12+ 222+ 2 2 1 2
cos 2) 󰇘1+ ( 2222 1 2 cos 2) 󰇘2 2 1 2
sin 2 (21
󰇗2
󰇗+2
󰇗2 ) – ( 1+ 2) 1 sin 1
2 2 sin ( 1+2) (28)
The force exerted at joint 2 is determined by:
2= ( 222+ 2 2 1 2 cos 2 ) 󰇘1+ 222󰇘2 -
2 1 2 sin( 2 ) 1
󰇗2
󰇗 - 2 2 sin ( 1+2)
(29)
The motion of the system is given by the
following form of a non-linear equation:
= 󰇘+󰇗,+() (30)
where, =1
2
󰇘=
󰇩(( 1+ 2)1
2+ 22
2+ 2 2 1 2 cos 2) ( 22
22 1 2 cos 2)
( 22
2+ 2 2 1 2 cos 2 ) 22
2󰇪
󰇗,=󰇩 2 1 2 sin 2 (21
󰇗2
󰇗+2
󰇗2 )
2 1 2 sin( 2 ) 1
󰇗2
󰇗󰇪
()
=( 1+ 2) 1 sin 1 2 2 sin ( 1+2)
2 2 sin ( 1+2)
=1
2
1B3 PID Controller Design
The equation resulting from Euler-Lagrange Eq.
(30) is a non-linear equation. In this equation, the
input F denotes the torque delivered to the robot,
but its value is unknown. Therefore, controlling the
force applied to the joints is necessary to achieve
the desired ultimate position. For our situation, we
employ the traditional linear PID control method.
Specifically, we require two PID controllers since
the movement of the first arm is influenced by the
movement of the second arm. Indeed, there is still
strong contact between the two arms. The
conventional linear proportional-integral derivative
(PID) control strategy is implemented, [20], [21].
= e + 󰇗 + (31)
Where = , is desired joint angle, the
variables , and represent the proportional,
integral, and derivative constants of the PID
controller, respectively. The closed-loop equation is
derived by substituting the control action F from
Equation (31) into the robot model Equation (30),
resulting in:
󰇘+󰇗,+()= e + 󰇗 +
(32)
WSEAS TRANSACTIONS on SYSTEMS and CONTROL
DOI: 10.37394/23203.2023.18.52
Aly M. Eissa, Mohamed Fawzy El-Khatib,
Mohamed I. Abu El-Sebah
E-ISSN: 2224-2856
490
Volume 18, 2023
From the system's model Eq. (30), we can have:
󰇘=( )1 󰇗, ()+
(33)
with = ( )1 (34)
We disengaged the system to incorporate the
new input. =1
2 (35)
However, the system receives actual torque input.
=󰇣1
2󰇤=()1
2 (36)
The error signals of the system are
e (1)= 11
e (2)= 22 (37)
where is the final positions and given by:
1
2=/2
/2
The initial position is denoted as:
1
2=󰇣/2
0󰇤
so, in our case:
1=1 e (1) + 1 󰇗1 + 1e (1)
2=2 e (2) + 2 󰇗2 + 2e (2)
recalling the physical actual torques:
=󰇣1
2󰇤
=()1 e (1)+ 1 󰇗1 + 1e (1)
2 e (2)+ 2 󰇗2 + 2e (2) (38)
So, the system equations are:
󰇩󰇘1
󰇘2󰇪=
( )1 󰇗, ()+
󰇩1 e (1) + 1 󰇗1 + 1e (1)
2 e (2) + 2 󰇗2 + 2e (2) 󰇪 (39)
4 Simulation and Results
As depicted in Figure 3, it is possible to acquire
approximate mathematical models and subsequently
simulate them in Matlab/Simulink using the
designed PID controller to enhance the system's
performance.
Fig. 3: Modeling of a two degree of freedom robot
arm
The PID controller helps to achieve the desired
final positions of m1 and m2, which are determined
by the angles θ1 and θ2, in a short duration, with
minimal overshoot, and with minimal error. Using
the following examples, this will be illustrated.
In Example 1, the simple concept of a two-link
depicted in Figure 1 is being considered. In this
work, we consider the following factors.
1= 2= 1 , 1= 2 , 2= 1
The desired final positions are:
1
2=/2
/2
The beginning locations, initial angular velocities,
and initial states are:
1
2=󰇣/2
0󰇤,󰇩󰇗1
󰇗2󰇪=󰇣0
0󰇤
PID settings for θ1 and θ2 are selected as:
1=30 , 1=15 , 1=20
2=30 , 2=10 , 2=20
Figure 4 displays the starting and desired
locations of the robot. Subsequently, we graph the
positions θ1 and θ2 of m1 and m2 as a function of
time within the range [0,5] in Figure 5.
In Figure 6 illustrates the disparity between our
desired destination and our current location.
(1)= 11, e (2)= 22
The desired coordinates are denoted as θ1f and
θ2f, whereas the numerical approximations derived
by solving the system using Matlab/Simulink are
represented by θ1(t) and θ2(t). The results suggest
that the PID controller rapidly achieves the desired
positions of m1 and m2, as solved by the angles θ1
and θ2, within a brief time period of approximately
5 seconds, with minimal error. Finally, in Figure 7,
we illustrate the torques f1 and f2 versus time.
WSEAS TRANSACTIONS on SYSTEMS and CONTROL
DOI: 10.37394/23203.2023.18.52
Aly M. Eissa, Mohamed Fawzy El-Khatib,
Mohamed I. Abu El-Sebah
E-ISSN: 2224-2856
491
Volume 18, 2023
(a)
(b)
Fig. 4: (a) Initial two-link position (b) Two link
target position for example 1.
(a)
(b)
Fig. 5: (a) m1's position in relation to time (b) m2's
position in relation to time for example 1.
(a)
(b)
Fig. 5: (a) the errors e (1)= 1(t) 1f versus
time (b) the errors e (2)= 2(t) 2f versus time
for example 1.
(a)
(b)
Fig. 6: (a) the torque of 1 versus time (b) the
torque of 2 versus time for example 1 .
Example 2. We replicate the preceding example
while maintaining all parameters constant, with the
exception of the final positions, in which we utilize
1
2=/4
/4
WSEAS TRANSACTIONS on SYSTEMS and CONTROL
DOI: 10.37394/23203.2023.18.52
Aly M. Eissa, Mohamed Fawzy El-Khatib,
Mohamed I. Abu El-Sebah
E-ISSN: 2224-2856
492
Volume 18, 2023
Figure 8 illustrates the initial and target
positions of m1 and m2, respectively. The positions
θ1 and θ2 of m1 and m2 with respect to time are
illustrated in Figure 9. We illustrate the
discrepancies between the estimated and target
positions in Figure 10. We conclude by displaying
the torques versus time in Figure 11. Once more,
the PID controller obtains the final positions of m1
and m2 in a brief amount of time (5 seconds
approximately), as demonstrated by these results.
(a)
(b)
Fig. 7: (a) Initial two link position (b) Two link
target position for example 2.
(a)
(b)
Fig. 8: (a) m1's position in relation to time (b) m2's
position in relation to time for example 2.
(a)
(b)
Fig. 9: (a) the errors e (1)= 1(t) 1f versus
time (b) the errors e (2)= 2(t) 2f versus time
for example 2.
(a)
(b)
Fig. 10: (a) the torque of 1 versus time ( b) the
torque of 2 versus time for example 2.
Example 3. Consider the robot illustrated in
Figure 1 with the subsequent parameters in this
instance:
1= 2= 1 , 1= 2 , 2= 1
The final target positions are:
WSEAS TRANSACTIONS on SYSTEMS and CONTROL
DOI: 10.37394/23203.2023.18.52
Aly M. Eissa, Mohamed Fawzy El-Khatib,
Mohamed I. Abu El-Sebah
E-ISSN: 2224-2856
493
Volume 18, 2023
1
2=󰇣0
0󰇤
Initial states, positions, and velocities are taken as:
1
2=󰇣/2
0󰇤,󰇩󰇗1
󰇗2󰇪=󰇣0
0󰇤
The PID constants denoted as θ1 and θ2 are:
1=30 , 1=15 , 1=20
2=30 , 2=10 , 2=20
Figure 12 illustrates the starting and ending
positions of the robot. The positions θ1 and θ2 of m1
and m2 as a function of time within the interval
[0,5] are illustrated in Figure 13. The discrepancies
θ1 and θ2 between the target position and the
numerically estimated position are illustrated in
Figure 14. It once more requires only a few seconds
to determine the target's location. It should be noted
that the PID controller rapidly calculates the final
positions of m1 and m2 (in seconds) with an
extremely small margin of error. Figure 15
concludes with torques f1 and f1 as a function of
time.
(a)
(b)
Fig. 11: (a) m1's position in relation to time, (b)
m2's position in relation to time, for example 3.
(a)
(b)
Fig. 12: (a) the position of m1 versus time (b) the
position of m2 versus time for example 3.
(a)
(b)
Fig. 13: (a) the errors e (1)= 1(t) 1f versus
time (b) the errors e (2)= 2(t) 2f versus time
for example 3.
WSEAS TRANSACTIONS on SYSTEMS and CONTROL
DOI: 10.37394/23203.2023.18.52
Aly M. Eissa, Mohamed Fawzy El-Khatib,
Mohamed I. Abu El-Sebah
E-ISSN: 2224-2856
494
Volume 18, 2023
(a)
(b)
Fig. 14: (a) the torque of 1 versus time ( b) the
torque of 2 versus time for example 3.
Example 4. Ultimately, we examine the robot
illustrated in Figure 1 while implementing the
subsequent parameters:
1= 2= 1 , 1= 2 , 2= 1
The final target positions are:
1
2=󰇣/2
0󰇤
Initial states, positions, and velocities are taken as:
1
2=󰇣/2
0󰇤,󰇩󰇗1
󰇗2󰇪=󰇣/2
0󰇤
The PID constants denoted as θ1 and θ2 are:
1=30 , 1=15 , 1=20
2=30 , 2=10 , 2=20
Figure 16 illustrates the starting and ending
positions of the robot. Figure 17 illustrates the
relationship between the timestamps [0, 5] and the
positions θ1 and θ2 of m1 and m2, respectively. The
discrepancies e(θ1) and e(θ2) between the target and
the approximate positions obtained numerically are
illustrated in Figure 18. It takes only a few seconds
to obtain the objective position, as in the preceding
instances. In conclusion, Figure 19 illustrates the
torques f1 and f1 as a function of time.
(a)
(b)
Fig. 15: (a) m1's position in relation to time, (b)
m2's position in relation to time, for example 4.
(a)
(b)
Fig. 16: (a) the position of m1 versus time (b) the
position of m2 versus time for example 4.
WSEAS TRANSACTIONS on SYSTEMS and CONTROL
DOI: 10.37394/23203.2023.18.52
Aly M. Eissa, Mohamed Fawzy El-Khatib,
Mohamed I. Abu El-Sebah
E-ISSN: 2224-2856
495
Volume 18, 2023
(a)
Fig. 17: (a) the errors e (1)= 1(t) 1f versus
time (b) the errors e (2)= 2(t) 2f versus time
for example 4
(a)
(b)
Fig. 18: (a) the torque of 1 versus time ( b) the
torque of 2 versus time for example 4.
5 Conclusion
This paper examines a two-link robotic manipulator
and models its dynamics using Lagrange
mechanics. Initially, we obtained the dynamic
equation of the robot by employing the Euler-
Lagrange method, and then an effective controller
was developed. The PID controller was
implemented to regulate the robot's movement to a
designated location. Specifically, we explain using a
PID controller to maintain the links at a s pecified
position. The results demonstrate the efficacy of the
PID controller in different cases. The study
suggested can be utilized to develop and program
control algorithms for a mobile robot. These
techniques enable us to stabilize inverted
pendulums on a mobile robot. There are multiple
potential coding options for implementing this PID
control, which depend on the specific sensors
employed to measure the angles of the connections.
This study analyzed a robot with rotational joints
operating in a two-dimensional plane. However, the
PID controller described in this study can be
expanded to accommodate robots with prismatic
joints. Our plans involve exploring intricate joints,
including a ball and socket joint.
References:
[1] Eissa, Aly M.; ATIA, Mostafa R.; ROMAN,
Magdy R. An effective programming by
demonstration method for SMEs industrial
robots. Journal of Machine Engineering,
2020, 20.
[2] Baccouch, M.; Dodds, S. A. Two-Link robot
manipulator: simulation and control
design. International Journal of Robotic
Engineering, 2020, 5.2: 1-17.
[3] El-Khatib, Mohamed Fawzy; Maged, Shady
A. Low level position control for 4-DOF arm
robot using fuzzy logic controller and 2-DOF
PID controller. In: 2021 International
Mobile, Intelligent, and Ubiquitous
Computing Conference (MIUCC). IEEE,
2021. p. 258-262.
[4] RL Burden, JD Faires, and AM Burden
(2016) Numerical analysis. Cengage
Learning, Boston, MA.
[5] El-Khatib, Mohamed Fawzy, et al.
Experimental Modeling of a New Multi-
Degree-of-Freedom Fuzzy Controller Based
Maximum Power Point Tracking from a
Photovoltaic System. Applied System
Innovation, 2022, 5.6: 114.
[6] JYS Luh (1983), Conventional controller
design for industrial robots a tutorial. IEEE
Transactions on Systems, Man, and
Cybernetics SMC-13: 298-316.
[7] J Shah, S Rattan, B Nakra (2015) Dynamic
analysis of two-link robot manipulator for
control design using computed torque
control. International Journal of Research in
Computer Applications and Robotics 3: 52-
59.
WSEAS TRANSACTIONS on SYSTEMS and CONTROL
DOI: 10.37394/23203.2023.18.52
Aly M. Eissa, Mohamed Fawzy El-Khatib,
Mohamed I. Abu El-Sebah
E-ISSN: 2224-2856
496
Volume 18, 2023
[8] G Nandy, B Chatterjee, and A Mukherjee
(2018) Dynamic analysis of a two-link robot
manipulator for control design. Advances in
Communication, Devices, and Networking,
Springer, 767-775.
[9] JS Kumar and EK Amutha (2014) Control
and tracking of robotic manipulator using
PID controller and hardware in loop
simulation. International Conference on
Communication and Network Technologies,
IEEE.
[10] Mohammed and Eltayeb (2018) Dynamics
and control of a two-link manipulator using
PID and sliding mode control. International
Conference on Computer, Control, Electrical,
and Electronics Engineering (ICC- CEEE),
IEEE.
[11] NK Chaturvedi, L Prasad (2018) A
comparison of computed torque control and
sliding mode control for a three-link srobot
manipulator. International Conference on
Computing, Power, and Communication
Technologies (GUCON), IEEE.
[12] J Romero, L Diago, J Shinoda, and I
Hagiwara (2015) Evaluation of brain models
to control a robotic origami arm using
holographic neural networks. International
Design Engineering Technical Conferences
and Computers and Information in
Engineering Conference, 57137.
[13] DM Wolpert, RC Miall, M Kawato (1998)
Internal models in the cerebellum. Trends in
cognitive sciences 2: 338-347.
[14] El-Sebah, M. I. A. (2016). Simplified
intelligent Universal PID
Controller. International Journal of
Engineering Research, 5(1), 11-15.
[15] CH Edwards, DE Penney, and DT Calvis
(2016) Differential equations and boundary
value problems. Pearson Education Limited.
[16] El-Sebah, M. I. A., Syam, F. A., Sweelem, E.
A., & El-Sotouhy, M. M. (2023). A Proposed
Controller for an Autonomous Vehicles
Embedded System. WSEAS Transactions on
Circuits and Systems, 22, 1-9.
[17] Nandy, G., Chatterjee, B., & Mukherjee, A.
(2018). Dynamic analysis of two-link robot
manipulator for control design. In Advances
in Communication, Devices and Networking:
Proceedings of ICCDN 2017 (pp. 767-775).
Springer Singapore.
[18] Khalate, A. A., Leena, G., & Ray, G. (2011).
An adaptive fuzzy controller for trajectory
tracking of robot manipulator. Intelligent
Control and Automation, 2(4), 364-370.
[19] Spong, M. W., & Vidyasagar, M.
(2008). Robot dynamics and control. John
Wiley & Sons.
[20] Aner, E. A., Awad, M. I., & Shehata, O. M.
(2023). Modeling and Trajectory Tracking
Control for a Multi-Section Continuum
Manipulator. Journal of Intelligent & Robotic
Systems, 108(3), 49.
[21] Aner, E. A., Awad, M. I., & Shehata, O. M.
(2024). Performance evaluation of PSO-PID
and PSO-FLC for continuum robot’s
developed modeling and control. Scientific
Reports, 14(1), 733.
Contribution of Individual Authors to the
Creation of a Scientific Article (Ghostwriting
Policy)
The authors equally contributed in the present
research, at all stages from the formulation of the
problem to the final findings and solution.
Sources of Funding for Research Presented in a
Scientific Article or Scientific Article Itself
No funding was received for conducting this study.
Conflict of Interest
The authors have no conflicts of interest to declare.
9BCreative Commons Attribution License 4.0
(Attribution 4.0 International, CC BY 4.0)
This article is published under the terms of the
Creative Commons Attribution License 4.0
https://creativecommons.org/licenses/by/4.0/deed.e
n_US
WSEAS TRANSACTIONS on SYSTEMS and CONTROL
DOI: 10.37394/23203.2023.18.52
Aly M. Eissa, Mohamed Fawzy El-Khatib,
Mohamed I. Abu El-Sebah
E-ISSN: 2224-2856
497
Volume 18, 2023