INT J COMPUT COMMUN, ISSN 1841-9836 9(3):253-260, June, 2014. Solving Continuous Trajectory and Forward Kinematics Simultaneously Based on ANN C.K. Ang, S.H. Tang, S. Mashohor, M.K.A.M. Arrifin Chun Kit Ang*, Sai Hong Tang, Syamsiah Mashohor, Mohd Khairol Anuar Mohd Arrifin Universiti Putra Malaysia Department of Mechanical and Manufacturing Engineering, Faculty of Engineering, 43400 UPM, Serdang, Selangor Darul Ehsan. Email: ack_kit@hotmail.com, saihong@upm.edu.my, syamsiah@upm.edu.my, khairol@upm.edu.my *Corresponding author Abstract: Robot movement can be predicted by incorporating Forward Kinematics (FK) and trajectory planning techniques. However, the calculations will become complicated and hard to be solved if the number of specific via points is increased. Thus, back-propagation artificial neural network is proposed in this paper to overcome this drawback due to its ability in learning pattern solutions. A virtual 4-degree of freedom manipulator is exploited as an example and the theoretical results are compared with the proposed method. Keywords: Artificial Neural Network (ANN), back propagation neural network, forward kinematics, continuous trajectory. 1 Introduction Trajectory planning can be considered as an important issue in robot industry. Without an appropriate trajectory planning, a robot’s motion will become unpredictable and it may collide with obstacles or go through undesirable points. Thus, an appropriate trajectory planning enables us to determine the required workspace and provides us an opportunity to avoid obstacles. Basically, there are two types of trajectory planning, point to point and continuous trajectory (with via points). However, continuous trajectory planning will be more practical compare to point to point trajectory because it allows robot to pass through various specific points and it is useful for real time robot. Conventionally, there are a few methods that can be used for continuous trajectory planning such as Bezier function, Linear Segments with Parabolic Blends (LSPB), and high order polyno- mials. Unfortunately, those methods require extensive calculations when the number of specific points is increased and thus leading to the emergence of a large number of formulas ( [1]- [5]). Hence, it is advisable to develop a method which is able to overcome this drawback. 2 Preliminaries Forward kinematics (FK) can be used to determined the position and orientation of a robot’s hand if all the configurations are known and the equations can be derived by using Denavit- Hartenberg (DH) method because it is the standard way of modelling the robot motion due to its simplicity of modelling robot links and joints that is applicable for any robot configuration s regardless of its complexity. The total transformation for a robot manipulator from base to hand will be Copyright © 2006-2014 by CCC Publications 254 C.K. Ang, S.H. Tang, S. Mashohor, M.K.A.M. Arrifin RTH = RT 11 T2 2T3... n−1Tn = A1A2A3...An =   nx ox ax px ny oy ay py nz oz az pz 0 0 0 1   (1) and the end effector can be defined as: re(t) = fe(θ(t)) (2) where re ∈ Rm in Cartesian space is related to the joint space vector, m is dimensional position vector of end effector. In fact, what we are actually interested in is the inverse kinematics (IK) because it allows us to determine the value of each joint in order to place the arm at a desired position and orientation. The inverse kinematic problem is to find the joint variable θ for any givenre(t). Unfortunately, it is impossible to find an analytic solution due to the nonlinearity off(θ(t))in reality. The inverse kinematics problem of manipulators is thus usually solved at the velocity level. Differentiating re(t) = fe(θ(t)) with respect to time yields a linear relation between the Cartesian velocity ṙeand the joint velocityθ̇: Je(θ)θ̇ = ṙe (3) where Je(θ) ∈ Rm×n is the end effector Jacobian matrix which is defined as Je(θ) = ∂f(θ) ∂θ [6- 13]. However, the derived IK equations are not necessarily available when the degeneracy and singularity problems ( [6], [9], [12]- [14])] occurred and thus we need to use some new methods to solve it such as artificial neural network, genetic algorithm, neural fuzzy and etceteras ( [7]- [15]). Generally, high order polynomial is used to plan a trajectory with the intention to let the robot’s hand to pass through all the specific points. However, solving the high order polynomial equations requires extensive calculations. Instead, it is advisable to use combinations of lower order polynomials for different segments of the trajectory and blend them together to satisfy all required boundary conditions ( [1]- [5]). θ (t) = c0 + c1t + c2t 2 + ....... + cn−1t n−1 + cnt n (4) For an example, for a 4-3-4 trajectory, a fourth order polynomial is used to plan a trajectory between the initial point and the first via point, followed by a third order polynomial to plan a trajectory between two via points, lastly another fourth order polynomial is implemented to plan the trajectory between the last via point and final angle. θ (t)1 = a0 + a1t + a2t 2 + a3t 3 + a4t 4 θ (t)2 = b0 + b1t + b2t 2 + b3t 3 θ (t)3 = c0 + c1t + c2t 2 + c3t 3 + c4t 4 In short, IK allows us to allocate the robot’s hand at desired location and the motion of robot’s hand can be determined by incorporating the FK and trajectory techniques. Sadly, the calcula- tions will become tedious and hard to be solved when the number of specific points is increased. Solving Continuous Trajectory and Forward Kinematics Simultaneously Based on ANN 255 3 Theoretical and Simulation Results Experiments were performed on a simulated 4-degree of freedom (DOF) robot manipulator which shown in Figue 1, IK was used to determine the starting and ending configurations for the robot’s hand while the high order polynomials and FK were used to track the motion of the robot’s hand from beginning to the end in Cartesian space. It was specified that the robot need to pass through two specific points. At the same time, velocities and accelerations constraints need to be taken into consideration. Figure 1: Simulated 4 DOF manipulator Assuming that a manipulator needs to spend tf to complete the moving path and a manip- ulator joint needs to reach θaat interval time ta then θbat interval time tb where ta < tband ta, tb ∈ [0, tf]. One may need to match the position, velocity, and accelerations of the two seg- ments at each point to plan a continuous trajectory. Hence, higher order polynomials in the form of θ (t) = C0 + C1t + C2t2 + ... + Cn−1tn−1 + Cntn are required. However, it is an extensive calculation process to solve high order polynomial and it is advisable to use the combinations of lower order polynomials for different segment of the trajectory such as 4-3-4 trajectory or 3-5-3 trajectory. The velocity and acceleration for initial and final point are zero. In order to fulfill the entire initial, final, and via points requirement, a matrix form can be generated where 256 C.K. Ang, S.H. Tang, S. Mashohor, M.K.A.M. Arrifin tab = tb − taand tc = tf − ta − tb.  θ1 θ̇1 θ̈1 θ2 θ2 0 0 θ3 θ3 0 0 θ4 θ̇4 θ̈4   =   1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1 ta t 2 a t 3 a t 4 a 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 1 2ta 3t 2 a 4t 3 a 0 −1 0 0 0 0 0 0 0 0 0 2 6ta 12t 2 a 0 0 −2 0 0 0 0 0 0 0 0 0 0 0 1 tab t 2 ab t 3 ab 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 1 2tab 3t 2 ab 0 −1 0 0 0 0 0 0 0 0 0 0 2 6tab 0 0 −2 0 0 0 0 0 0 0 0 0 0 0 1 tc t 2 c t 3 c t 4 c 0 0 0 0 0 0 0 0 0 0 1 2tc 3t 2 c 4t 3 c 0 0 0 0 0 0 0 0 0 0 0 2 6tc 12t 2 c   ×   a0 a1 a2 a3 a4 b0 b1 b2 b3 c0 c1 c2 c3 c4   Or [θ] = [M] [C] (5) By solving those constant values in matrix[C], the joint turning angle at any interval time can be obtained where θ (t) = a0 + a1t + a2t 2 + a3t 3 + a4t 4 0 < t ≤ ta θ (t) = b0 + b1t + b2t 2 + b3t 3 t ∈ [ta, tb] , t = t − ta θ (t) = c0 + c1t + c2t 2 + c3t 3 + c4t 4 t ∈ [tb, tf] , t = t − ta − tb The equation which is used to represent the robot’s hand at any interval time can be denoted as: rE (ti) =   cos (θ1 (ti)) [ l1 × cos (θ2 (ti)) + l2 × cos ( 3∑ k=2 θk (ti) ) + l3 × cos ( 4∑ k=2 θk (ti) )] sin (θ1 (ti)) [ l1 × cos (θ2 (ti)) + l2 × cos ( 3∑ k=2 θk (ti) ) + l3 × cos ( 4∑ k=2 θk (ti) )] l1 × sin (θ2 (ti)) + l2 × sin ( 3∑ k=2 θk (ti) ) + l3 × sin ( 4∑ k=2 θk (ti) )   (6) In fact, all these calculations can be solved simultaneously by back-propagation artificial neu- ral network. The back-propagation neural network can be activated by presented a training set data with inputs x1(p), x2(p)...xn(p)and desired outputsyd,1(p), yd,2(p), ..., yd,n(p). Assume that the back-propagation network consists of three layers which are input layer, hidden layer, Solving Continuous Trajectory and Forward Kinematics Simultaneously Based on ANN 257 and output layer. The actual outputs of the neurons in the hidden layer will be yj(p) = sigmoid [ n∑ i=i xi(p) × wij(p) − θj ] where n is the number of inputs for neuron j in the hidden layer, and sigmoid is the sigmoid activation functionY sigmoid = 1/(1+e−X). For the output layers, the actual outputs of the neurons will be yk(p) = sigmoid [ m∑ j=1 xjk(p) × wjk(p) − θk ] where m is the number of inputs for neuron k in the output layer. An error signal ek(p) = yd,k(p) − yk(p)will be generated from neuron kat output layer and propagated backward for updating the weights. For updating the weights at the output neurons with learning rate, α: Error gradient,δk(p) = yk(p) × [1 − yk(p)] × ek(p) ek(p) = yd,k(p) − yk(p) Weight correction, ∆wjk(p) = α × yj(p) × δk(p) Update weight, wjk(p + 1) = wjk(p) + ∆wjk(p) Similar to output layer, for updating the weights at the hidden neurons with learning rate, α: Error gradient,δj(p) = yj(p) × [1 − yj(p)] × 1∑ k=1 δk(p) × wjk(p) Weight correction, ∆wij(p) = α × xi(p) × δj(p) Update weight,wij(p + 1) = wij(p) + ∆wij(p) The same procedures can be repeated by increasing the iteration puntil the output error criterion is satisfied. A training data set which consists of inputs and outputs is presented to the networks for learning purpose. Inputs consists of the final angle of each joint θf,n and interval time variable ti where ti ∈ [0, tf] and tf is the time for the manipulator to complete the moving path. The outputs will be the coordinates of robot’s hand at any interval time with respect to ti,rE(ti) = [px py pz] T . There are two set of results in table 1. The theoretical results which obtained by using conventional FK and high order polynomial trajectory were compared to the artificial neural network (ANN) results. The robot started moving from its initial position (θ1=θ2=θ3=θ4=0) and passed through two via points before it reached its destinations. It shows that the robot still able to pass through those specific points even though the destination point was changed and the moving path could be tracked by using ANN. The theoretical and ANN results were almost the same and the errors were less than ±0.3unit (less than 1%). This can be used as an evidence to proof that artificial neural network is able to solve FK and continuous trajectory simultaneously due to its adaptive learning ability. Since back-propagation neural network is able to track the motion of end effector, it can be used to track the position of each joint in Cartesian space as well. Referring to Figure 1, Joint 1 and joint 2 are located at the origin of reference frame, (0,0,0). For tracking the position of joint 3, the training data set inputs and outputs will be [ti θ1(ti) θ2(ti)] T and rE,3(ti). Correspondingly, for joint 4, the training data set inputs and outputs will be [ti θ1(ti) θ2(ti) θ3(ti)] T and rE,4(ti). Once the joins location of all joints are computed, the manipulator link equations can be derived 258 C.K. Ang, S.H. Tang, S. Mashohor, M.K.A.M. Arrifin by using parametric equations. Assuming that the location and vector for joint m and joint n at any interval time ti: rE,n(ti) = [px,n py,n pz,n] T , −−→ OPn = [an bn cn] T and rE,m(ti) = [px,m py,m pz,m] T , −−−→ OPm = [am bm cm] T . The link equation that connecting joint n and m will be x−px,n an−am = y−py,n bn−bm = z−pz,n cn−cm = ζ or [x y z] T = [px,n py,n pz,n] T + [an − am bn − bm cn − cm]T ζ For the robot manipulator which is mentioned in this paper, the robot link equations can be denoted as: Link 1: x−px,3 a3−a2 = y−py,3 b3−b2 = z−pz,3 c3−c2 = ζ2 0 ≤ z ≤ pz,3 Link 2: x−px,4 a4−a3 = y−py,4 b4−b3 = z−pz,4 c4−c3 = ζ3 pz,3 ≤ z ≤ pz,4 Link 3: x−px,5 a5−a4 = y−py,5 b5−b4 = z−pz,5 c5−c4 = ζ4 pz,4 ≤ z ≤ pz,5 Conclusively, the link equation can be derived as long as the coordinates of two successive joints are provided by using back-propagation neural network and the links parametric equations can be derived based on the vector of the two successive joints. Once the equation of each manipulator link is known, a person is able to predict or compute the entire motion of a robot manipulator. Besides, obstacle collision can be detected if the link equations are known. Assuming that there is a rigid body obstacle enclosed in a sphere which possesses a r radius and center locates at (xo, yo, zo), the sphere equation will be (x − xo)2 + (y − yo)2 + (z − zo)2 = r2 The intersection points between the link and obstacle can be obtained by solving the link and sphere surface equation. For an example, a line that pass through the point (e, f, g)possessing a same direction as vector[a b c]T , the equation for the link will be: x−e a = y−f b = z−g c = ζor   x y z   =   e f g   +   a b c   ζ Substituting the link equation into sphere surface equation yields, (aζ + e − xo)2 + (bζ + f − yo)2 + (cζ + g − zo)2 = r2 simplified and yields, Aζ2 + 2Bζ + C = 0 where, A = a2 + b2 + c2 B = a(e − xo) + b(f − yo) + c(g − zo) C = (e − xo)2 + (f − yo)2 + (g − zo)2 − r2 Solving Continuous Trajectory and Forward Kinematics Simultaneously Based on ANN 259 By examining the discrimination roots, the intersection points between link and sphere surface exists when∆ ≥ 0, [a(e − xo) + b(f − yo) + c(g − zo)]2 ≥ 4 [ a2 + b2 + c2 ] [ (e − xo)2 + (f − yo)2 + (g − zo)2 − r2 ] The intersection point between the manipulator links and obstacle can be determined by solving the constant ζ. Table 1: Comparison of Conventional and ANN Techniques in Tracking Robot End Effector Moving Path 4 Conclusions This paper shows that back-propagation neural network is able to solve trajectory and kine- matic problems simultaneously. The moving path of the robot end effector still able to be tracked even though the ending point is changed. Besides, this method can be used to track the position of robot joints which can be used to derive the robot link equations. In comparison to conven- tional continuous trajectory planning methods, ANN is much easier to be applied and provide high accuracy results. 260 C.K. Ang, S.H. Tang, S. Mashohor, M.K.A.M. Arrifin Bibliography [1] Saeed B. N. (2001). Introduction to Robotics Analysis, System, Application. Prentice Hall, 29-172. [2] Ata, A., Myo, T. (2008). Optimal trajectory planning and obstacle avoidance for flexible manipulators using generalized pattern research. World J. Modeling and Simulation, 4:163–171. [3] Guan, Y., Yokoi, K. , Stasse, O. , Kheddar, A. (2005). A. On robotic trajectory planning using polynomial interpolations. Proc. IEEE Int. Conf. on Robotics and Biomimetics, 111-116. [4] Reichenbach, T, Kovacic, Z.(2005). Collision-Free Path Planning in Robot Cells Using Virtual 3D Collision Sensors. Cutting Edge Robotics, 683–697. [5] Campos, J., Flores, J.A.R., Montufar, C.P.(2008). Robot Trajectory Planning for Multiple 3D Moving Objects Interception: A Polynomial Interpolation Approach. Proc. IEEE Int. Conf. on Electronics, Robotics and Automotive Mechanics, 478–483. [6] Zarkandi S., Vafadar A., Esmaili M. R.(2011). PRRRRRP redundant planar parallel manip- ulator: Kinematics, workspace and singularity analysis. IEEE 5th Int. Conf. on Robotics, Automation and Mechatronics (RAM), DOI: 10.1109/RAMECH.2011.6070457, 61–66. [7] Al-Mashhadany, Y. I. (2010). Inverse Kinematics Problem (IKP) of 6-DOF Manipulator by LRNNs. Int. Conf. on Management and Service Science (MASS), 1 – 5. [8] Zhang, D., Lei, J.(2011). Kinematic analysis of a novel 3-DOF actuation redundant par- allel manipulator using artificial intelligence approach. Robotics and Computer-Intergrated Manufacturing, 27: 157–163. [9] Firmani, F., Podhoprodeski, R. P.(2009). Singularity analysis of planar parallel manipulatos based on forward kinematic solutions. Mechanism and Machine Theory, 44: 1386–1399. [10] Vesselenyi, T., Dzitac, S., Dzitac, I., Manolescu, M.J. (2007). Fuzzy and Neural Controllers for a Pneumatic Actuator. Int J Comput Commun, ISSN 1841-9836, 2(4):375-387. [11] Alvandar, S., Nigam, M. J. (2008). Neuro-Fuzzy based approach for inverse kinematics solution of industrial robot manipulators. Int J Comput Commun, ISSN 1841-9836, 3(3):224–234. [12] Mahidzal, D., and Jian-Ding, T. (2011). Forward and Inverse Kinematics Model for Robotic Welding Process Using KR-16KS KUKA Robot. Proc. IEEE Int. Conf. on Modeling, Simu- lation and Applied Optimization, 1–6. [13] Shah, J., Rattan S. S., Nakra, B.C.(2011). Kinematic Analysis of 2-DOF planer robot using artificial neural network. World Academy of Science, Engineering and Technology, 81: 282–285. [14] Parikh, J.P., Lam, S.S. (2009). Solving the forward kinematics problem in parallel manipu- lators using an iterative artificial neural network strategy. Int. J. Adv. Manuf. Technol., 40: 595–606. [15] Her, M.-G., Chen, C.Y., Karkoub, M. (2002). Approximating a Robot Inverse Kinematics Solution Using Fuzzy Logic Tuned by Genetic Algorithms. Int. J. Adv. Manuf. Technol., 20: 375–380.