Abstract
The redundant manipulators have more DOFs (degree of freedoms) than it requires to perform specified task. The inverse kinematic (IK) of such robots are complex and high nonlinear with multiple solutions and singularities. As such, modern Artificial Intelligence (AI) techniques have been used to address these problems. This study proposed two AI techniques based on Neural Network Genetic Algorithm (NNGA) and Particle Swarm Optimization (PSO) algorithm to solve the inverse kinematics (IK) problem of 3DOF redundant robot arm. Firstly, the forward kinematics for 3 DOF redundant manipulator has been established. Secondly, the proposed schemes based on NNGA and PSO algorithm have been presented and discussed for solving the inverse kinematics of the suggested robot. Thirdly, numerical simulations have been implemented to verify the effectiveness of the proposed methods. Three scenarios based on triangle, circular, and sine-wave trajectories have been used to evaluate the performances of the proposed techniques in terms of accuracy measure. A comparison study in performance has been conducted and the simulated results showed that the PSO algorithm gives 7% improvement compared to NNGA technique for triangle trajectory, while 2% improvement has been achieved by the PSO algorithm for circular and sine-wave trajectories.
1 Introduction
The robot is a mechanical device which needs no breaks, and it can operate continuously. Furthermore, the robot outperformed the human workers in terms of speed and accuracy. The forward kinematics (FK) and inverse kinematics (IK) are the essential mathematical tools in controlling and path planning of robotic manipulators. The FK models are used to determine the position of the end effector based on joint angles as input variables. The opposite of FK is the IK, which works to determine the joint angles based on the Cartesian coordinates of the end effector [1–5].
The robot manipulators are classified as redundant and non-redundant robots according to their DOFs and the dimension of working space which is satisfying for specified tasks. The redundant manipulators have more DOFs (degree of freedoms) than it requires to perform a specified task. The 3 DOF manipulators which move in two dimensional plan are examples of redundant robot. In non-redundant robot manipulator, the dimension of workspace is equivalent of the number of DOFs for the robot. The 2DOF robot arm, which has two links and two joints, is an example of non-redundant robot [6, 7].
Redundant robot manipulators have been used in many difficult industrial tasks. An Inverse kinematic (IK) of redundant robot was not easily solved so that many researchers need to interface this robot's mathematical model with Artificial Intelligence (AI) to solve this problem [7–9].
Aggogeri et al. [10] presented fuzzy logic technique to solve the IK problem to improve the convergence of robot workspace. Shaher et al. [11] utilized two different Genetic Algorithms: the conventional GA and the continuous GA. The IK problem of 3-DOF robot arm has been viewed as an optimization problem. It has been shown that continuous GA outperforms the traditional one in terms of convergence speed. Duka et al. [12] used a feed-forward neural network to find the inverse kinematics of 3-DOF robot by generating the desired trajectories in the Cartesian space. Takatani et al. [13] proposed a neural network structure for solving the inverse kinematics of 3-DOF redundant robot. By hybridization of many neural network structures, the approach achieved good learning performance. Using training data based on postures, endpoints, and cost function, the approach can synthesize the neural network model for solution of inverse kinematics. Habibkhah et al. [14] proposed non-conventional neural network and virtual vector function method to solve the inverse kinematics (IK) of a 3-DOF redundant manipulator robot. Batista et al. [15] used Least Squares (LS), Recursive Least Square (RLS), and dynamic parameter identification algorithm based on Particle Swarm Optimization (PSO) with search space defined by RLS. Kelemen et al. [16] proposed an algorithm that takes into account joint limit avoidance, kinematic singularities avoidance, and an obstacle avoidance when controlling a kinematically redundant manipulator. The potential field approach is employed for end-effector path planning from the starting point to the end point. By using Jacobian-based technique and weight matrices to different tasks, the inverse kinematic model is developed. The other study presented focuses on the development of a low-cost robotic arm with three degrees of freedom designed for various applications, particularly in industry. Some traditional robotics concepts like acquisition, image processing, and object manipulation, were used. Artificial neural networks were utilized for two crucial functions: camera calibration and inverse kinematics resolution. The results from the application of artificial neural networks (ANNs) allowed for the control of the servo motors' trajectory for the robot [17].
In another study, the authors combined the two algorithms GA and NN to provide an inverse kinematics solution for a 3DOF redundant robot. The three-link robot's location and orientation are the inputs. The back-propagation neural network (BPNN) is receiving these inputs. A feed-forward neural network is added to the training of the error backpropagation technique via the BPNN model. This model has outstanding multi-dimensional function mapping capabilities and the capacity to classify arbitrarily complicated patterns. Continuous GA is used to optimize the BPNN weights. The difference between the estimated and desired joint angle outputs is also calculated, as is the Mean Square Error. The fitness function in GA was proposed [18].
The swarm behavior of some animals, such as bird flocks and fish schools, inspired the development of particle swarm optimization (PSO) [19–23]. It has several benefits such as straightforward implementation, global optimal solution with high probability and efficiency, quick convergence, and low computing time. The PSO is useful for solving challenging problems for high complex and nonlinear models [24–27]. Therefore, the PSO algorithm has been proposed as optimization tool for solving the inverse kinematics problem of a three-link redundant robot arm [28]. One can summarize the main contributions by the three main points:
- ❑Establishing the possible points covering the workspace of redundant robot manipulator based on FK.
- ❑Proposing optimization-based techniques to solve the IK problem based on NNGA and PSO algorithms
- ❑Conducting a comparison study between the proposed techniques in terms of accuracy measure.
The organization of this article is put into five sections. The second section presented the forward kinematics of 3-DOF redundant robot arm. The proposed methodology has been discussed in the third section. The fourth section conducted the numerical simulation to verify the effectiveness of the proposed approaches. The fifth section highlighted the main points deduced from the simulated results.
2 The forward kinematics of 3-DOF redundant robot arm
The forward kinematics (FK) of redundant robot is implemented to determine the location and orientation of end-effector for 3-DOF redundant robot manipulator as illustrated in Fig. 2 [18, 28, 29].
The robot manipulator has three arms of lengths
Table 1 shows the Denavit-Hartenberg (DH) parameter of the 3DOF redundant robot. The structure 3-DOF redundant manipulator can be described in terms of three variables; namely,
Link parameter table of 3DOF redundant robot
Link number | ||||
1 | 2 | 0 | 0 | |
2 | 2 | 0 | 0 | |
3 | 2 | 0 | 0 |
3 Methodology
The methodology described the equations of NNGA and PSO algorithms. Then the proposed flowchart is also presented. It involved the implementation of these two algorithms. Next the MSE and the accuracy founded of each algorithm.
3.1 The proposed NNGA algorithm
The NNGA is a combination of the GA algorithm and NN model. The three-link robot's end effector position and orientation are the inputs (
Figure 4 shows the mechanism of NNGA approach. The inputs to the proposed method are the positions and orientation of end-effector (1st block) using Eq. (1) and Eq. (2). The back-propagation neural network (BPNN) algorithm is implemented based on received inputs (see 2nd block). The result of BPNN is the rotation of end effector
Setting of continuous GA's parameters
Number of population | 30 |
Number of generation | 30 |
Crossover rate | 80% |
Mutation rate | 15% |
Number of variables | |
Lower and upper limits of variable (rad) |
It is worthy to mention that the forward kinematics have been utilized to train ANN for IK.
3.2 The proposed PSO algorithm
The mechanism of the proposed method based on PSO algorithm can be described by Figure 5. The mechanism consists of three stages. The first stage is the input to the PSO algorithm (1st block). The PSO algorithm receives these inputs for optimization purpose (2nd block); the mechanism results in optimal value of
The parameters of PSO
Parameter Description | Value |
Number of iteration | 100 |
Values of cognitive parameter | 1.9 |
Values of constant ( | 0.95 |
Number of Variables | |
Lower and upper limits of variable (rad) |
The flowchart of proposed schemes is shown in Figure 6. The flowchart begins with the random generation of positions and orientations of the 3DOF robot redundant arm based on forward kinematics. These points are chosen to lie within the robot's workspace. Then the proposed methods, NNGA and PSO algorithm, are applied. Furthermore, the output from each two approaches is the best values of orientation
4 Simulation results and discussion
The MATLAB programming software has been used to verify the proposed methods to solve the IK problem of 3-DOF redundant arm. The dimension of each length link is 2 m as indicted in Table (1). Eq. (1) and Eq. (2) are applied to perform forward kinematics (FK). There are 1,000 positions (
The triangle trajectory has been generated based on proposed NNGA and PSO algorithms as illustrated in Figure 8. The start point of the triangle trajectory is the same as the end trajectory. The trajectory ends at coordinates x = 2.0100, y = 1.0110 based on NNGA algorithm (blue line), it ends at x = 2.000 and y = 1.000 based on PSO algorithm (black line). The black-colored trajectory, which belongs to PSO algorithm, is more accurate than the trajectory, which belongs to NNGA algorithm, as shown in Figs 8 and 9.
The circular trajectories are simulated based on the proposed NNGA and PSO algorithms. The red-colored trajectory belongs to NNGA, while the black-colored trajectory belongs to PSO algorithm. The start and end points of a circular trajectory are the same. The trajectory ends at coordinates = 2.0034 and y = 2.0013 based on NNGA algorithm (red line), while it ends x = 4.0000, y = 2.0000 based on PSO algorithm (black line).
The sine-wave trajectories are simulated based on the proposed NNGA and PSO algorithms as shown in Figure 10. In case of NNGA method, the start of orientation
In these simulated scenarios, 52 points of end effector positions have been taken for each circular and triangle trajectories the simulated number. On the one hand, 15 orientations have been used for end effector orientation in case of sine-wave trajectory. The MSE has been used as accuracy indicator of the proposed NNGA and PSO algorithms for each trajectory. According to Table 4, the accuracy based on PSO algorithm is better than that based on NNGA method for all suggested trajectories.
Evaluation of MSE based on proposed methods
Trajectory | Algorithm | MSE |
Triangle trajectory | proposed NNGA | |
proposed PSO | ||
Circular trajectory | proposed NNGA | |
proposed PSO | ||
Sin-wave trajectory | proposed NNGA | |
proposed PSO |
Figure (11) shows the spectrum of accuracy values of the proposed methods for three trajectories as follows:
- ❑In case of triangular trajectory, the accuracy based on PSO algorithm equals 0.92%, which is better than the accuracy of the NNGA method which is equal to 0.855%. This indicates that an improvement ratio of 7% is obtained.
- ❑In case of circular trajectory, the accuracy based on PSO algorithm equals 0.9%, which is better than the accuracy of the NNGA method which is equal to 0.88%. This indicates that an improvement ratio of 2% is obtained.
- ❑In case of circular trajectory, the accuracy based on PSO algorithm equals 0.96%, which is better than the accuracy of the NNGA method which is equal to 0.94%. This indicates that an improvement ratio of 2% is obtained.
The main difference between previous works [18, 20] and this work is that objective functions (Eq. (14) for GA and Eq. (17) for PSO) have been proposed in this paper. These proposed equations solved inverse kinematic joint angle (
Comparison with related works
References and algorithm | Circular trajectory (x, y) (m) | Objective function | MSE (m) |
[18] NNGA (2018) | (2.098, 1.9708) | ||
Proposed NNGA | (2.0034, 2.0013) | ||
[20] PSO (2019) | (4.0131, 2.0059) | ||
Proposed PSO | (4.000, 2.000) |
The behavior of fitness function with respect to generation in case of NNGA method is shown in Figure 12. According to the figure, the best fitness value based on proposed NNGA is equal to
Figure 13 shows the behavior of fitness function with respect to generation in case of PSO algorithm. According to the figure, the best fitness value based on proposed PSO algorithm is equal to
5 Conclusion
The inverse kinematics of redundant manipulators is complex and its solution is a challenging problem. This study proposed NNGA and PSO algorithm to solve the inverse kinematics problem of 3DOF redundant robot arm. The performance of the proposed techniques has been evaluated in terms of accuracy. The MSE has been used as accuracy indicator for the solution based on these approaches. In the sense of solution accuracy, a comparison study has been made between the proposed methods based on numerical simulation. Three trajectories have been tested using the proposed methods. According to simulated results, it has been shown that the accuracies due to PSO algorithm is better than that based on NNGA approach for all suggested trajectories. The improvement in accuracy has been determined and it is found that a 7% improvement in accuracy is obtained using PSO algorithm in case of triangular trajectory, while 2% improvement has been recorded in case of circular and sine-wave trajectories. In addition, this study has been compared to previous works in the literature. It has been shown that the proposed solution schemes outperform the other techniques.
This study can be extended for future work by suggesting other modern optimization techniques or using embedded system design to implement the proposed algorithms to reduce the calculation efforts [34–45].
References
- [1]↑
J. J. Craig, Introduction to Robotics: Mechanics and Control, Third Edition USA: Pearson Prentice Hall, 2005.
- [2]
Mordechai Ben-Ari and Francesco Mondada, Elements of Robotics. Cham, Switzerland: Springer Nature, 2018.
- [3]
M. L. Muhammed, A. J. Humaidi, and E. H. Flaieh, “Towards comparison and real time implementation of path planning methods for 2R planar manipulator with obstacles avoidance,” Math. Model. Eng. Probl., vol. 9, no. 2, pp. 379–389, 2022. https://doi.org/10.18280/mmep.090211.
- [4]
M. L. Muhammed, A. J. Humaidi, and E. H. Flaieh, “A comparison study and real-time implementation of path planning of two arm planar manipulator based on graph search algorithms in obstacle environment,” ICIC Express Letters, vol. 17, no. 1, pp. 61–72, 2023. https://doi.org/10.24507/icicel.17.01.61.
- [5]
M. L. Muhammed, E. H. Flaieh, and A. J. Humaidi, “Embedded system design of path planning for planar manipulator based on Chaos A* algorithm with Known-obstacle Environment,” J. Eng. Sci. Technol., vol. 17, no. 6, pp. 4047–4064, 2022.
- [6]↑
F. A. Raheem, H. Z. Khaleel, and M. K. Kashan, (2018, December). Robot arm design for children writing ability enhancement using cartesian equations based on ANFIS. In 2018 Third Scientific Conference of Electrical Engineering (SCEE) (pp. 150–155). IEEE.
- [7]↑
P. K. Artemiadis, P. T. Katsiaris, and K. J. Kyriakopoulos, “A biomimetic approach to inverse kinematics for a redundant robot arm,” Autonomous Robots, vol. 29, pp. 293–308, 2010.
- [8]
J-Q. Xuan and S-H. Xu, “Review on kinematics calibration technology of serial robots,” Int. J. precision Eng. manufacturing, vol. 15, pp. 1759–1774, 2014.
- [9]
D. Vu, “Application of robots for welding inspection in the shipbuilding industry,” , in Trends, Paradigms, and Advances in Mechatronics Engineering, IGI Global, 2023, pp. 143–161.
- [10]↑
F. Aggogeri, B. Alberto, R. Adamini, and R. Faglia, “A fuzzy logic to solve the robotic inverse kinematic problem,” Appl. Mech. Mater., vol. 772, pp. 488–493, 2015.
- [11]↑
S. Momani, S. Zaer, A. Hammour, and O. M. K. Alsmadi, “Solution of inverse kinematics problem using genetic algorithms,” Appl. Math. and Inf. Sci., vol. 10, no. 1, p. 225, 2016.
- [12]↑
A-V. Duka, “Neural network based inverse kinematics solution for trajectory tracking of a robotic arm,” Proced. Technol., vol. 12, pp. 20–27, 2014.
- [13]↑
H. Takatani, N. Araki, T. Sato, and Y. Konishi, “Neural network-based construction of inverse kinematics model for serial redundant manipulators,” Artif. Life Robotics, vol. 24, pp. 487–493, 2019.
- [14]↑
S. Habibkhah and R. V. Mayorga, “An ANN and virtual vector function approach for the computation of the inverse kinematics of redundant manipulators,” WSEAS Trans. Inf. Sci. Appl., vol. 18, pp. 131–140, 2021.
- [15]↑
J. Batista, D. Souza, L. Dos Reis, A. Barbosa, and A. Rui, “Dynamic model and inverse kinematic identification of a 3-DOF manipulator using RLSPSO,” Sensors, vol. 20, no. 2, p. 416, 2020.
- [16]↑
M. Kelemen, I. Virgala, T. Lipták, Ľ. Miková, F. Filakovský, and V. Bulej, “A novel approach for a inverse kinematics solution of a redundant manipulator,” Appl. Sci., vol. 8, pp. 2229–2311, 2018.
- [17]↑
D. Santos, M. Cabral, R. H. C. Palácios, M. Mendonça, J.A. Fabri, and W. F. Godoy, “A neural autonomous robotic manipulator with three degrees of freedom,” Int. J. Intell. Syst., vol. 37, no. 9, pp. 5597–5616, 2022.
- [18]↑
H. Z Khaleel, “Inverse kinematics solution for redundant robot manipulator using combination of GA and NN,” Al-Khwarizmi Eng. J., vol. 14, no. 1, pp. 136–144, 2018.
- [19]↑
M. Shaikh and D. Yadav, “A review of particle swarm optimization (PSO) algorithm,” Technology (IJMET), vol. 13, no. 7, pp. 19–44, 2022.
- [20]↑
A. J. Humaidi and M. Hameed, “Development of a new adaptive backstepping control design for a non-strict and under-actuated system based on a PSO tuner,” Information, vol. 10, no. 2, pp. 1–17, 2019. https://doi.org/10.3390/info10020038, 38.
- [21]
A. J. Humaidi and H. M. Badr, “Linear and Nonlinear Active Disturbance Rejection Controllers for single-link flexible joint robot manipulator based on PSO tuner,” J. Eng. Sci. Technol. Rev., vol. 11, no. 3, pp. 133–138, 2018. https://doi.org/10.25103/jestr.113.18.
- [22]
R. F. Hassan, et al. “FPGA based HILL Co-Simulation of 2dof-PID controller tuned by PSO optimization algorithm,” ICIC Express Lett., vol. 16, no. 12, pp. 1269–1278, 2022. https://doi.org/10.24507/icicel.16.12.1269.
- [23]
A. J. Humaidi, S. K. Kadhim, and A. S. Gataa, “Optimal adaptive magnetic suspension control of rotary impeller for artificial heart pump,” Cybernetics Syst., vol. 53, no. 1, pp. 141–167, 2022. https://doi.org/10.1080/01969722.2021.2008686.
- [24]↑
M. N. Ajaweed, M. T. Muhssin, A. J. Humaidi, and A. H. Abdulrasool, “Submarine control system using sliding mode controller with optimization algorithm,” Indonesian J. Electr. Eng. Comput. Sci., vol. 29, no. 2, pp. 742–752, 2023. https://doi.org/10.11591/ijeecs.v29.i2.
- [25]
A. Al-Jodah, et al. “PSO-based optimized neural network PID control approach for a four wheeled omnidirectional mobile robot,” Int. Rev. Appl. Sci. Eng., vol. 14, no. 1, pp. 58–67, 2023. https://doi.org/10.1556/1848.2022.00420.
- [26]
N. Q. Yousif, et al. “Performance improvement of nonlinear differentiator based on optimization algorithms,” J. Eng. Sci. Technol., vol. 18, no. 3, pp. 1696–1712, 2023.
- [27]
A. J. Humaidi, et al. “Design of optimal sliding mode control of PAM-actuated hanging mass,” ICIC Express Lett., vol. 16, no. 11, pp. 1193–1204, 2022. https://doi.org/10.24507/icicel.16.11.1193.
- [28]↑
H. Z Khaleel, “Enhanced solution of inverse kinematics for redundant robot manipulator using PSO,” Eng. Technol. J., vol. 37, no. 7 part (A), 2019.
- [29]↑
S. Sood and P. Kumar “Modelling and simulation of 3R robotic arm,” Advanced Production and Industrial Engineering: Proceedings of ICAPIE 2022 Vol. 27, p. 329, 2022.
- [30]↑
L. Biagiotti and C. Melchiorri, Trajectory Planning for Automatic Machines and Robots, Springer Science and Business Media, 2008.
- [31]
E. Herman, G. Strang, W. Radulovich, E. A. Rutter, D. Smith Kirsten, R. Messer Alfred, K. Mulzet, et al. “Calculus volume 2” 2016.
- [32]↑
S. Li, W. Chen, K. Singh Bhandari, D.W. Jung, and X. Chen, “Flow behavior of AA5005 alloy at high temperature and low strain rate based on arrhenius-type equation and back propagation artificial neural network (BP-ANN) model,” Materials, vol. 15, no. 11, p. 3788, 2022.
- [33]↑
F. F. Shero, G. T. Saeed Al-Ani, E. J. Khadim, and H. Z. Khaleel, “Assessment of linear parameters of electrohysterograph (EHG) in diagnosis of true labor,” Ann. Trop. Med. Publ. Health, vol. 23, no. 4, pp. 139–147, 2020.
- [34]↑
H. Z. Khaleel, A. K. Ahmed, S. Abdulkareem, M. Al-Obaidi, S. Luckyardi, D.F. Al Husaeni, R.A. Mahmod, and A.J. Humaidi, “Measurement enhancement of ultrasonic sensor using pelican optimization algorithm for robotic application,” Indonesian J. Sci. and Technol., vol. 9, no. 1, pp. 145–162, 2024.
- [35]
T. Ghanim, A. R. Ajel, and A. J. Humaidi, “Optimal fuzzy logic control for temperature control based on social spider optimization,” IOP Conf. Ser. Mater. Sci. Eng., vol. 745, no. 1, 2020, Art no. 012099, . https://doi.org/10.1088/1757-899X/745/1/012099.
- [36]
Z. A. Waheed and A. J. Humaidi, “Design of optimal sliding mode control of elbow wearable exoskeleton system based on whale optimization algorithm,” J. Européen des Systèmes Automatisés., vol. 55, no. 4, pp. 459–466, 2022. https://doi.org/10.18280/jesa.550404.
- [37]
A. Q. Al-Dujaili, A. J. Humaidi, Z. T. Allawi, and M. E. Sadiq, “Earthquake hazard mitigation for uncertain building systems based on adaptive synergetic control,” Appl. Sys. Innov., vol. 6, no. 2, p. 34, 2023. https://doi.org/10.3390/asi6020034.
- [38]
A. H. Jaleel and T. M. Kadhim, “Spiking versus traditional neural networks for character recognition on FPGA platform,” J. Telecommunication, Electron. Comput. Eng., vol. 10, no. 3, pp. 109–115, 2018.
- [39]
A. J. Humaidi, S. Hasan, and M. A. Fadhel, “FPGA-based lane-detection architecture for autonomous vehicles: a real-time design and development,” Asia Life Sci., no. 1, pp. 223–237, 2018.
- [40]
A. J. Humaidi, S. Hasan, and M. A. Fadhel, “Rapidly-fabricated nightly-detected lane system: an FPGA implemented architecture,” Asia Life Sci., no. 1, pp. 343–355, 2018.
- [41]
R. F. Hassan, et al. “FPGA based HIL Co-simulation of 2DOF-PID controller tuned by PSO optimization algorithm,” ICIC Express Lett., vol. 16, no. 12, pp. 1269–1278, 2022.
- [42]
A. F. Hasan, et al. “Fractional order extended state observer enhances the performance of controlled tri-copter UAV based on active disturbance rejection control,” in Mobile Robot: Motion Control and Path Planning, vol. 1090, A. T. Azar, I. Kasim Ibraheem, and A. Jaleel Humaidi, Eds., Cham: Springer, 2023. https://doi.org/10.1007/978-3-031-26564-8_14.
- [43]
J. H. Amjad, S. Hasan, and M. A. Fadhel, “FPGA-based lane-detection architecture for autonomous vehicles: areal-time design and development,” Asia Life Sci., no. 1, pp. 223–237, 2018.
- [44]
M. Y. Hassan, A. J. Humaidi, and M. K. Hamza, “On the design of backstepping controller for Acrobot system based on adaptive observer,” Int. Rev. Electri. Eng., vol. 15, no. 4, pp. 328–335, 2020. https://doi.org/10.15866/iree.v15i4.17827.
- [45]
A. F. Hasan, N. Al-Shamaa, S. S. Husain, A. J. Humaidi, and A. Al-dujaili, “Spotted Hyena Optimizer enhances the performance of Fractional-Order PD controller for Tri-copter drone,” Int. Rev. Appl. Sci. Eng., 2023. https://doi.org/10.1556/1848.2023.00659.