Content area

Abstract

Formulating mathematical models and deriving efficient algorithms are crucial for meeting the requirements of future robotics applications. This paper proposes a novel approach for analyzing kinematic systems and computing inverse kinematics (IK) solutions for serial robotic arms. The aim is to reduce modeling complexity and the computational cost of IK solution algorithms, while enhancing accuracy and efficiency by reformulating the kinematic equations using simplified constraints. This is achieved by integrating the rotation matrix and the unit quaternion to represent kinematic equations in a simple and unified form without compromising the degrees of freedom or raising the order of the kinematic equations, as in traditional approaches. The method combines analytical and numerical techniques to obtain an exact IK solution in two steps: first, the wrist joint variables are substituted into the position equations, resulting in a modified position vector equation obtained analytically; second, numerical iteration is applied to compensate for the error between the current and desired positions, leading to the ultimate exact inverse solution. The method is tested on a 5R robot and a 6R (UR-10) robot with an offset wrist to demonstrate the mathematical process and real-time algorithm performance. The results demonstrate that the absolute position error is less than 1015 m, with no orientation error, and the mean calculation time for the IK solution is less than 5 ms. Furthermore, the results indicate higher accuracy and reduced computational time compared to other common IK methods. Moreover, the algorithm’s improved performance in processing continuous paths demonstrates its advantages in both simulation and practical applications. Finally, the proposed methodology is expected to advance further research in kinematic modeling and enhance polynomial-based numerical iterative algorithms.

Full text

Turn on search term navigation

1. Introduction

The mathematical modeling of the kinematic analysis of rigid bodies and the studies of robotic kinematics have received increasing attention in recent decades [1]. This research aims to provide simplified and elegant mathematical formulas to reduce computational complexity and derive efficient equations and solutions for problems related to the kinematic and dynamic modeling of robotics, computer graphics, and the analysis of mechanisms [2,3,4].

In kinematic topology and serial robotics, inverse kinematic (IK) solutions are complex due to non-linearity and coupled equations [5]. In addition, the wrist configuration plays an important role in determining suitable approaches for kinematic solutions in decoupled robotic arms [6]. Many industrial robot designs and research efforts focus on designing the geometric structures that conform to the Pieper criterion, in which the three consecutive joint axes of the robot intersect at a common point [7]. This type of wrist configuration involves an elegant geometric design that enables analytical closed-form IK solutions [8]. Therefore, analytical methods (i.e., closed-form) are considered the most effective for solving IK problems, particularly for mechanisms with simple structures [9,10]. In contrast, when closed-form solutions are unavailable, numerical methods are commonly used to solve IK problems for redundant or continuous robotic arms [11]. However, some deficiencies with numerical approaches may occur, and iterative convergence fails to find accurate or reliable solutions [12]. Due to the complexity of IK problems for 6-revolute (6R) robots, many theories with different approaches are used in mathematical and physical applications to represent the modeling of kinematic bodies, which are expressed in various parameters and forms for analyzing the forward kinematic (FK) and IK of robotic arms [13,14,15,16,17].

Lee et al. [18] proposed a method to decouple the positioning and wrist of the PUMA robot by breaking it into two sub-chains and then calculating the three joint variables of position using geometric methods [7]. These approaches are applicable only to robot arms with spherical wrists and decoupled robot arms. For robot arms with non-spherical wrists or those with special geometric structures, such as a hollow wrist (virtual wrist), Wu et al. [19] introduced a method to simplify the wrist structure by applying the virtual wrist center concept. Initially, they derived an approximate analytical solution for a 6R robot with a spherical wrist. The Levenberg–Marquardt (LM) method was then used to calculate the exact solutions. Although this approach improves accuracy, solving the actual kinematic equation in the first step leads to increased computational time in subsequent steps. Wang et al. [20] and Zhou et al. [21] extended the virtual wrist concept to obtain accurate solutions. The IK solution of the simplification mechanism is close to the actual solutions in the [19] method. Their methods reduce the number of iterations and improve computational efficiency by employing the damped least squares (DLS) algorithm and the Newton–Raphson (NR) iterative technique to obtain the final solutions. Metin Toz et al. [22] applied this method to develop a meta-heuristic optimization algorithm for the IK solution of serial robot arms with offset wrists. However, these methods sometimes fail due to workspace loss caused by artificial simplification. To address this issue, Li et al. [23] proposed a modified method based on the same concept. This method compensates for the loss of workspace by introducing additional parameters into the position equation and comparing results with the NR method. However, this approach increases the number of parameters and variables in the kinematic position equation.

The aforementioned methodologies demonstrate that the numerical solution processes are affected by geometric configurations of robotic wrists, the properties of kinematic system equations, and the applied simplification techniques. Consequently, classical analytical or numerical IK solution principles may be unsuitable for achieving accurate and efficient solutions or are difficult to apply without geometric limitations in general 6R serial robot arms [2,24]. Therefore, further study is required for kinematic modeling of mechanisms, in general, and the IK solution approaches in particular. This can be achieved through our work, which is based on reordering the kinematic equations and reducing certain variables, thereby deriving new kinematic equations with optimized variables to obtain more accurate and effective results. As a result, the key contributions of this paper include the following:

We introduce a novel approach for solving and improving the IK solution that is achieved by deriving a new kinematic equation resulting from the integrating of the rotation matrix with a quaternion, utilizing tangent-half angles as a univariate to describe the kinematic modeling of the position and orientation of the robot arm’s end effector (EE) with non-redundant variables.

We reconstruct the robot’s equations of motion using a non-redundant parameter set, analytically integrating the structural vectors and wrist joint variables with the position variables, without losing any degrees of freedom or changing the working space of the robot arm.

The proposed approach reduces computational cost by requiring only position variables as inputs; orientation variables are computed independently outside the algorithm.

The structure of this paper is as follows: Section 2 presents the mathematical framework for robot kinematics modeling and discusses the limitations of related work. Section 3 introduces rotation operations using univariate rotation matrices and quaternions, along with a kinematic analysis that integrates both representations to reduce variables. Section 4 presents the new kinematic equations and details the proposed iterative IK algorithm based on wrist joint compensation. Section 5 evaluates the algorithm using a 6R (UR-10) robot arm, compares it with NR and DLS methods, and applies it to a polishing trajectory task. Finally, Section 6 concludes the paper.

2. Mathematical Framework for Robot Kinematics Modeling and Limitations of Related Work

   This section provides a short overview of general robot configurations and typical wrist structures, followed by a brief discussion of IK solution methodologies that have been recently proposed, highlighting their shortcomings. Finally, the mathematical problem that needs to be developed in the related literature is formulated.

2.1. The Kinematics Modeling

This section provides an overview of relevant fundamental mathematical concepts to facilitate understanding of the derivation of the kinematic equations. Regarding the topological symbols used in this work (Scbda), the index at the upper left superscript and the right subscript of the symbols indicate the coordinate frames. The upper right superscript and the subscript represent the successive (i-th) joint angles, while the subscript on the lower-left is used to define an element within a specific coordinate frame or a designated abbreviation. The major symbols used in this paper are illustrated in the Nomenclature table, and further symbols are defined in the rest of the paper.

2.1.1. Natural Coordinate System

According to our recent research, we proposed the concept of the natural coordinate system for parameter calibration and dynamic modeling of robotic systems. A natural coordinate system is defined as each link of the kinematic system in the Cartesian coordinate system naturally coinciding with the base coordinate system when the robot is in its initial configuration (initial time), where the origin of each coordinate frame is located on the corresponding rotational axis. Taking the kinematic system as a whole and robot system in particular, the natural coordinate system provides a concise and uniformed expression of robotic parameters, making it more suitable for kinematic analysis and precise systematic modeling of robot systems [8]. In this study, we also adopt the natural coordinate system to establish kinematic models, which will be the basis for deriving the IK formulations.

2.1.2. Robot Arm and Wrist Configurations

The kinematic systems and the robotic arm wrists are often designed with a unique structure to reduce the joint constraints of the structures and allow the position vectors to be decoupled from orientation vectors. The most common types are (a) spherical (Euler) wrist, in which axes 4, 5, and 6 intersect at a single point (the wrist center); (b) non-spherical (offset) wrist, in which axes 4 and 5 intersect at one point, and axes 5 and 6 intersect at another as illustrated in Figure 1. In some configurations, there is no direct common intersection among the last three axes [25].

Based on the definition of the natural coordinate system mentioned above, the vector vl=vx,vy,vzT represents the rotational axis of joint, while the joint angle (θl) defines the magnitude of rotation about this axis. The position vector rkb describes the sequential translation from the base to the EE of the robot arm.

In the initial state of the robotic system (zero-reference configuration), all joint variables are set to zero. Under this condition, each link coordinate frame coincides with the base (body) coordinate frame. Consequently, the position vector of the k-th link is equal to its corresponding link vector (rk=lk), where k=1,2,,n, and is defined as the vector measured from the origin of frame (k1) to the origin of frame (k). For a single link, we denote (rk=ll). The vector ll represents the link’s length and offset in a single-column vector form, given by ll=lx,ly,lzT, where lx, ly, and lz are the Cartesian components of the link vector, as described in detail in [8,26].

For rigid bodies, the rotation and kinematics of a robot arm can be mathematically described by Rodrigues’ rotation formula as

(1)Rl=I+sin(θl)·v^l+(1cos(θl))·v^l2,

Rl=cl+vx2(1cl)vxvy(1cl)vzslvxvz(1cl)+vyslvxvy(1cl)+vzslcl+vy2(1cl)vyvz(1cl)vxslvxvz(1cl)vyslvyvz(1cl)+vxslcl+vz2(1cl)=r11r12r13r21r22r23r31r32r33

where sl=sin(θl), cl=cos(θl), and the orientation and position of the robot arm EE with respect to the base coordinate frame can be represented as follows:

(2)Rnb=k=b+1k=n(Rk1b)·Rkk1,b<n,

(3)rnb=k=b+1k=n(Rk1b·lk).

where b refers to the base frame. In the rest of the paper, the base frame (b) is denoted as frame zero (0). The FK of n-DOF kinematic system or robot can be represented by Equations (2) and (3), which express the robot arm’s position and orientation, respectively [8].

2.2. Inverse Kinematics of 6R Robot Arms with Wrist Simplification: Related Work

The literature has focused on the kinematic analysis and IK solution for 6-DOF (6R) robot arms, which are widely used because they provide the minimum necessary control for full 3D positioning and orientation. The robot arms with fewer than 6-DOF cannot reach all arbitrary poses, while those with more than 6-DOF are redundant, increasing IK computational complexity. From Equation (3), the position vector of the 6R robot arm can be expressed as

(4)r60=l1+R10·l2+R20·l3+R30·l4+R40·l5+R50·l6.

To obtain the IK solution, particularly by simplifying the kinematic constraints, the process can generally be divided into three main steps:

2.2.1. Kinematic Analysis for Wrist Decoupling

The simplification method begins by decoupling the arm joints, separating the position controlling joints from the orientation controlling wrist joints. From Equations (3) and (4), the position vector of the 6R robot arm can be expressed as

(5)r60=r30+r63,r60=k=13Rk10·lk+R30·k=46Rk13·lk,

where r30 and r63 represent the position vector equations of the first three joints and the last three joints, respectively, wherein the r63 depends on the geometric configuration of the wrist.

This is applied to avoid the effects of the first three joints during simplification; then we rearrange Equation (5) as

(6)r60r30=r63,r60r30=R30·k=46Rk13·lk.

2.2.2. Simplification of the Position Equation

The kinematic constraints of the robotic arm are simplified by adjusting the position of the original frame to conform to the Pieper criterion [7]. This process involves artificially converting the robot wrist into a spherical (Euler) wrist. This is achieved by moving the axes of joints 5 and 6 along the axis of joint 4 until their Z-axes intersect at a common point (the wrist center) after simplification, as illustrated in Figure 1a.

As a result, the kinematic equations of the robotic arm become artificially compatible with the Pieper criterion [21,23], thereby facilitating the analytical derivation of initial IK solutions [19,20]. Consequently, the right part of Equation (6) becomes zero (r63=03, as r5=r6=0). Because the EE position of the simplified robotic arm is the same as the desired pose, Equation (5) can be expressed as follows:

(7)r60=r30=k=13Rk10·lkr60=l1+R10·l2+R20·l3+R30·l4=r6d0.

where r6d0=[Px,Py,Pz]T is the desired position of the robot arm’s EE shifted from link 6 to link 4, due to the artificial modification from a non-spherical wrist to a spherical (Euler) wrist in the simplification assumption.

2.2.3. Obtaining the Wrist Joint Variables

As no offset is related to the wrist joints after simplification, the position vector parameters become the base frame for the wrist coordinate frame. After artificial modification, Equation (3) becomes

(8)R63=R301·R60.

Consequently, the six joint angles of the simplified robot arm can be analytically obtained from Equations (7) and (8), which are formulated according to the Pieper criterion, as described in [19,20,21,23]. Obviously, the EE poses of the simplified robot arm are different from the actual desired pose; this combined (synthetic) error (ePose) can be defined as

(9)ePose=ep+eang,

where the position error ep=(r6d0r6s0) represents the difference between the actual (desired) position vector r6d0 and the approximate position vector r6s0, and the orientation error eang(vl,θl)=(R6s01·R6d0) represents the difference between the approximate R6s0 and actual (desired) R6d0 orientation matrix, respectively. From Equation (1), the incremental rotation ang(vl,θl) is

(10)vl=vxvyvz=12sinθlr32r23r13r31r21r12,

θl=arccosr11+r22+r3312

by combining the position and orientation errors into a single vector, as detailed in references [20,21], the overall error can be expressed as

(11)derr=[epeang]T,

where derr is the (6×1) vector, representing the differential motion vector corresponding to the infinitesimal motion of the robot arm’s EE from its approximate pose (position and orientation) to the desired posture [19,20,21]. According to the differential theory, the following relation is obtained:

(12)Δθ=D1·derr.

the Δθ indicates the joint angle increment and D represents a differential function used for the iterative process [19,20,21,23,25]. From Equation (12), the error between the robot manipulator’s current pose and the desired pose (with the offset wrist) is iteratively computed until the accurate joint variables are obtained.

To conclude, several shortcomings in the literature still require further investigation and improvement:

Real simplification: The methods mentioned above rely on artificial simplifications, resulting in a redundant computational process for obtaining the actual IK solutions.

Consideration of workspace: Most approaches do not consider the loss of the workspace due to the simplification from an offset wrist to Euler’s wrist Equation (7), which can lead to failure of the iterative method.

Reduction in variables: The iterative functions use the full set of parameters and matrix dimensions Equations (11) and (12), which increases the computational time and cost, especially for the IK solutions of the redundant kinematics systems.

Use of univariate equations: Indeed, the kinematic systems with univariate polynomial equations have been previously studied [12]. Nevertheless, it is not easy to obtain direct IK solutions from these approaches, as most of these methods need additional tools to obtain the equations’ roots. In addition, they contain some unnecessary solutions that must be eliminated, such as imaginary roots which increase the computational time and cost.

As described above, the kinematic problems of decoupled robots can be addressed by combining different solution methods to enhance a robot’s performance by leveraging the benefits and minimizing the drawbacks of each method. A hybrid approach is the focus of development in this research.

3. Reformulation of the Kinematic Equations

   In this section, the rotation matrix and the unit quaternion are reformulated to simplify the kinematic equations of the robot arm using a single variable to simplify the kinematic equations of the robot arm. A new and efficient formulation is then derived analytically, to improve IK solutions for robot arms with various wrist configurations using numerical methods.

3.1. Modification of the Kinematic Rotation Formula

This work uses a tangent half-angle in robot kinematic modeling rather than sine and cosine in the direction cosine matrix (DCM) and the unit quaternion. This approach allows the formulation of the position and orientation vectors of robotic arms and other kinematic systems in a unified set of polynomial vector equations. The second reason is that most equations of kinematics systems are transformed into tangent functions in IK analysis. Moreover, the tangent half-angle in vector polynomial systems is also considered optimal, as it is a resultant ratio of two components (sin(θl) & cos(θl)), which enhances elimination methods for deriving IK solutions and establishes new foundations for kinematic theories. This study extends and further develops the approach presented in [26].

3.1.1. The Direction Tangent Matrix

The rotation of multi-kinematic axis chains using the tangent half-angle is obtained by substituting the following equation:

(13)cos(θl)=1τl21+τl2,sin(θl)=2τl1+τl2.

into Equation (1) and then it is transformed into

(14)Ql=I+2·τl·v^l+τl2·I+2·v^l2,

where τl=tan(θl2) and (π<θl2<π) and

Ql=1+τl2·(2·vxvx1)2·τl·(vxvy·τlvz)2·τl·(vxvz·τl+vy)2·τl·(vxvy·τl+vz)1+τl2·(2·vyvy1)2·τl·(vyvz·τlvx)2·τl·(vxvz·τlvy)2·τl·(vyvz·τl+vx)1+τl2·(2·vzvz1).

the inverse of the direction tangent matrix (DTM) can be represented as

(15)Ql10=I2·τl·v^l+τl2·I+2·v^l2=Q0l.

the DTM modulus square can be expressed by multiplying Equation (14) with Equation (15), denoted as

(16)Ql0·Ql10=Q01l·Ql0=(τl0)2·I.

from Equation (16), the modulus τl0 of the DTM can be expressed for the multi axis system as follows:

(17)τn0=k=1n1+(τk0)2.

by considering Equations (1), (2), (14), and (16), the common factor between the DCM and the DTM can be expressed by the modulus τl0, as follows:

(18)Ql0=τl0·Rl0,

To express the equation of the position vector in the form of the half-tangent angle, we substitute Equation (18) in Equation (3), and then the unified position vector for the general robot arm is denoted as

(19)rn0·k=1nτk0=k=1nk=1nτk0·Qk10·lk.

The Qk0 and τk0 in Equation (19) are multiple 2-order vector equations; they effectively describe the kinematics of the robot and mechanisms in a single trigonometric variable (τl) and structure axis vector (vl). It is clearly shown that the rotation matrices in Equation (14) are isomorphic to the Rodrigues matrix in Equation (1); however, the squared modulus of sine and cosine functions strongly constrains the kinematic modeling analysis [2,15,24].

In contrast, the expression forms are more concise in kinematic transformations based on DTM, where the squared modulus is not equal to unity, as illustrated in (16). Moreover, because the transcendental sine and cosine rotation matrix parameters complicate the analysis of relationships between joint variables and structural vectors, we apply a tangent substitution, as in Equations (14), (16), and (19), combined with the properties of the DTM modulus in (17) to reduce the number of kinematic equations and simplify the rotational angles into a unified form, which is is more concise for describing the kinematics of a multi-DOF system [26,27,28,29].

3.1.2. The Tangent Quaternion

The quaternions are mathematical formulas used to represent the orientations of the robot arm EE. The unit quaternion is described as

(20)ql=vl·sin(θl/2),cos(θl/2)T,

by substituting the tan instead of the sin/cos angles, Equation (5) in a new form is expressed as

(21)Tl=vl·tan(θl/2),τ.lT=τl,τ.lT.

the vector part τl is sometimes known as the Rodrigues, Gibbs, or Caley vector [30]. Some mathematical operations and properties for non-orthogonal axes are shown in Table 1; for more details, see [26].

The tangent quaternion multiplication is calculated in the quaternion matrix form, which can represent rotation in FK as follows:

(22)Tn0=k=1n(T˜k1k2)·Tlk1,

where T˜k1k2 is the 4×4 matrix quaternion, written as

(23)T˜k1k2=τ.k1.I+τk1×τk1τk1Tτ.k14×4.

where τk× is a 3×3 skew symmetric matrix of vector part (τk).

The tangent quaternion represents the rotation in a compact and simple form as the reference part (τ.k) will not change in the single joint and the orthogonal successive axes rotations, further reducing the degrees of kinematic equations [26]. Therefore, this feature of a new quaternion is used for computing the IK solution shown in Section 4.

3.2. Kinematic Modeling of the 6R Robot Arm in a Unified Form

The motions of the kinematic system and 6R robot arm are described by Equations (2), (3), (18), and (19), wherein the general 6R robot arm only needs to establish the position and attitude equation with the first five joint variables. This is because the last joint only infinitely rotates the EE to align the attached tool [26].

Considering Equations (4) and (5) and based on Equations (17) and (18), the position equations of the 6R robot arm can be expressed using the half tangent of the joint angles (univariate (τl)) as follows:

(24)r60=τ50·l1+τ51·Q10·l2+τ52·Q20·l3+τ53·Q30·l4+τ54·Q40·l5+Q50·l6.

while orientation equations can be expressed in univariate matrix form using DTM (Equation (18)), the tangent quaternion offers a more efficient representation for the robot arm’s EE, requiring only three elements. Assuming that T50 aligns with the the desired attitude quaternion, which is denoted by T5d0, defined under the base frame, the orientation equation of a 6R robotic arm can then be formulated as

(25)T50=τ.50·T5d0,

where τ.50, the scalar element (fourth part) of the desired attitude quaternion (T50), is equal to unity (τ.50=1) for all adjacent orthogonal axes, whereas for parallel axes vl1vl, the value depends on the joint angle (π<θl/2<π) [26]. As the scalar element of the desired quaternion T5d0 is equal to 1, the orientation equations of the 6R robotic arm can then be formulated in vector form as follows:

(26)τ50=τ.50·τ5d0,

By considering Equations (2), (3), (19), and (22), it is required that the positions (r60, r6d0) of the robot arm’s EE and the desired orientations (T50, T5d0) be equal. Therefore, the kinematic modeling equations for a general 6R robotic arm, involving both the position and orientation vector, can be expressed in univariant vector (3×1) form as follows:

(27)position:τ50·l1+τ51·Q10·l2+τ52·Q20·l3+τ53·Q30·l4+τ54·Q40·l5+Q50·l6τ50·r6d0=03.orientation:τ50τ.50·τ5d0=03

3.2.1. Compact Position Equation of 6R Robot Arm

As part of the simplification process, the arm joints are decoupled into two sets: those responsible for controlling the EE position and those responsible for orientation. Based on Equation (6), the position vector of the 6R robot arm can be expressed in terms of the (τl) variable as follows:

(28)r60r30=1τ30·τ53·Q30·k=46τ5k1·Qk13·lk.

to simplify, we separate position variables from orientation variables. After substitution, Equation (28) becomes

(29)τ50·r60(τ50·l1+τ51·Q10·l2+τ52·Q20·l3)=Q30·(τ53·l4+τ54·Q43·l5+Q53·l6).

considering the properties in Equation (16), we multiply both sides by Q310 and note that the matrix inverse multiplication has the reverse order of the joint angles’ sequential as follows:

(30)Q310=Q23·Q12·Q01,

Equation (29) after rearranged is shown as follows:

(31)τ53·(Q03·(r60l1)(τ10·Q13·r2+τ20·Q23·l3)τ30·l4)=τ30·(τ54·Q43·l5+Q53·l6),

the right side of Equation (31) now depends only on wrist joint variables and their structural parameters. Thus, the wrist position equation is is denoted as

(32)τ30·k=45τ5k·Qk3·lk+1=τ30·(τ54·Q43·l5+Q53·l6)=τ30·1+τ52·Q43·l5+Q53·l6=τ30·(l5+l6)+2·τ4·v^4·l5+v^4·l6+2·τ5·(v^5·l6)+4·τ4·τ5·(v^4·v^5·l6)+τ42·V4·l5+V4·l6+τ52·(l5+V5·l6)+2·τ4·τ52·(v^4·l5+v^4·V5·l6)+2·τ42·τ5·(V4·v^5·l6)+τ42·τ52·(V4·l5+V4·V5·l6).

where Vl=I+2·v^l2.

3.2.2. Simplification of Wrist Variables and Structure

The variables τl,τ2,τ3 determine positions, while the other joints define the EE’s orientation. The orientation equation in quaternion form is given by

(33)T50=T30·T53.

to simplify the kinematic computation, the 4th and 5th wrist joint variables will be substituted from Equation (32) and replaced with robot arm structural parameters. From Equation (22), the attitude direction can be written as

(34)T53=τ4·v4+τ5·v5+τ4·τ5·v^4·v51τ4·τ5·v4T·v5=03v4v5v^4·v5100v4T·v54×4·1,τ4,τ5,τ4·τ5T,

by separating the joint variables from the structure parameters, Equation (34) results in

(35)T53=03E4511v4T·v5·1[3].1,τ4,τ5,τ4·τ5T,

where 1[3]=[001] and E45=v4,v5,v^4·v5. Now, the joints variables are separated from the structure parameters. Consider Equation (26); then the orientation equation is defined as

(36)T50=T30·T53=τ.50·T5d0.

referring to Equations (22) and (23), we multiply both sides of Equation (36) with T310; then,

(37)τ30·T53=τ.50·T˜3*0T5d0,

Note: the T3*0 is a conjugate quaternion; which expresses the inverse rotation of T30. Equations (22), (36), and (37) result in

(38)τ30·T53=τ.50·τ5×d0Iτ5d0τ5Td01·T30.

substitute Equation (35) in Equation (38) and then separate the structure matrix parameter from joint variables:

(39)τ30·03E4511v4T·v5·1τ4τ5τ4·τ5=τ.50·τ5×d0Iτ5d0τ5Td01·T30,

by consider Equation (35). If the E45 non-singular where DetE451=1; and E451=E45T, then, from Equation (39), we take the structure parameter matrix on the right side, and we obtain the following:

(40)τ30·1,τ4,τ5,τ4·τ5T=τ.50·C.·T30,

wherein

C.=v4T3·v54·1[3]·E45,1E45,03·τ5×d0Iτ5d0τ5Td01.

Equation (40) expresses the direction alignment equations based on the tangent quaternion. The left side of the equation includes the modulus invariance of the position part (τ30) and the orientation part of the robot wrist. The right side contains a matrix (C.), which is composed of two matrices. The first matrix is for the structural parameters of axes 4 and 5; the other matrix part is related to the desired orientation. The unique structural parameter matrix C. can be formulated in general form as

(41)C.ij=C.iT.C.j.

here, i and j denote the number of rows and columns in the matrix (C.), respectively. The features of the unique matrix, C. with a modular quaternion, are used for eliminating the variables of the last two axes of the robot arm wrist. From Equations (40) and (41), we can see that the parameters depend on the desired attitude of the EE and IK solutions of the position of the first three joints. Each row of Equation (40) can be written as

(42)τ30=τ.50·C.[1]·T30τ30·τ4=τ.50·C.[2]·T30τ30·τ5=τ.50·C.[3]·T30τ30·τ4·τ5=τ.50·C.[4]·T30

the first sub-equation, Equation (42), indicates the modulus invariance of quaternions with no wrist joint variables. The second and third sub-equations show the orientation alignment of axes 4 and 5, respectively. The last term of the equation contains the multiplication of τ4 and τ5, which seems to be redundant. Now, we substitute Equation (42) into Equation (32), and the wrist’s last two joints can be expressed as

(43)(τ30)2=(τ.50)2·T3T0C.11·T30(τ30)2·τ42=(τ.50)2·T3T0·C.22·T30(τ30)2·τ52=(τ.50)2·T3T0·C.33·T30(τ30)2·τ42·τ52=(τ.50)2·T3T0·C.44·T30(τ30)2·τ42·τ5=(τ.50)2·T3T0·C.24·T30(τ30)2·τ4·τ52=(τ.50)2·T3T0·C.34·T30,

where (τ.50)2=τ30·τ53τ50d.

This section simplified the robot arm’s kinematics by integrating the rotation matrix and quaternion using a univariate approach. The following section presents how this method effectively computes the IK solution for the 6R robot arm.

4. A Novel Algorithm for Simplifying 6R Robot Arm Inverse Kinematics

This section discusses the development of an algorithm for computing IK solutions for general 6R robotic arms with different configurations.

4.1. Position Joint Angles

The 6R robot arm position equation is rearranged and simplified to include only three variables, ensuring that wrist variables do not affect the position equation of robot arm’s EE. Because in many robot arms the first axis coincides with the base, it is assumed that l1=03. From Equations (32), (41), and (43), the simplified position equation is expressed as

(44)Psimp=τ10·Q13·l2+τ20·Q23·l3+τ30·l4Q03·r6d0+1τ50d·T3T0·C.11·T30·l5+l6+2·T3T0·C.12·T30·v^4·l5+v^4·l6+2·T3T0·C.13·T30·(v^5·l6)+4·T3T0·C.14·T30·(v^4·v^5·l6)+T3T0·C.22·T30·V4·l5+V4·l6+T3T0·C.33·T30·l5+V5·l6+2·T3T0·C.34·T30·v^4·l5+v^4·V5·l6+2·T3T0·C.24·T30·(V4·v^5·l6)+T3T0·C.44·T30·V4·l5+V4·V5·l6=03.

where Psimp is the 3×1 simplified position vector in FK.

To derive the IK solution of the 6R robots with general robotic wrists, the position equation’s three variables (θ1, θ2, and θ3), the synthetic error between the desired and current EE positions is evaluated to determine whether it is equal to zero or within the acceptable error tolerance (ε). From Equation (9), the position error is defined as

(45)Psimpep.

the position error (ep=Px2+Py2+Pz2 ) of the robot arm EE is usually set according to the accuracy required for the robot’s task planning.

From Equations (12) and (45), the compositional error between the desired and the current poses of the robot arm with the offset wrist is calculated through an iterative (pseudo-inverse) approach until the accurate joint variables are obtained.

(46)Δθ=J+·ep.

here, J+=JT(JJT)1 is left pseudo-inverse, and J is the Jacobian matrix. The matrix Jm×n has m rows and n columns. In our method, the number of rows is fixed at m=3, while the columns depend on the position joint variables after simplification, thus reducing to n=n2 compared to the n-DOF of the robot arm in the standard kinematic matrix in other methods.

Based on Equations (45) and (46), the algorithm searches for joint position variables in Cartesian space. The matrix size depends on the joint variables defined in the modified Equation (44), and the position error remains relatively small because wrist structure parameters are embedded into modified position equation. Unlike other existing simplification approaches [19,20,21], which assume no wrist offset and do not decouple position and orientation equations in the IK solutions, our method enables faster convergence in the IK solutions, reducing iteration time compared to conventional numerical approaches [25].

4.2. Wrist Joint Angles

The second step of the IK solution is completely different from the first position vector solution step. This method is unique, more concise, and computationally more efficient compared to those in [19,20,21]. The wrist orientation is primarily determined by axes 4 and 5, which control the attitude of the last joint connected to the EE. After solving for the first three joint variables, the 6R robot arm’s wrist angles are directly computed from Equation (42) as follows:

(47)τ4=C.[2]·T30C.[1]·τ30,τ5=C.[3]·T30C.[1]·τ30

Equation (47) shows that the joint angles of the wrist are totally dependent on the position modular (τ30) and position tangent quaternion (T30), where the structure axis vector of the matrix C. remains unchanged. In addition, Equation (47) is also not included in the IK iterative process, reducing computational time and cost. Compared with Equations (9) and (11) used in previous methods, the wrist joint angles are not affected by the orientation incremental error, thus improving accuracy.

4.3. IK Solution for 7R Robot Arm with Spherical and Non-Spherical Wrist

For a redundant robot, the EE position and orientation are determined according to the link offset between axes 6 and 7 for a 7R (i.e., hollow wrist, non-spherical wrist). The structure matrix C. is updated with new structure parameters for axes of rotation v5, v6, and T6d0, the desired attitude quaternion. Thus, the Equation (37) can be appeared as

(48)τ40·1,τ5,τ6,τ5·τ6T=τ.60·C.·T40.

the wrist equation, Equation (48), is related to the last joint variables τ5 and τ6, which are substituted with the position quaternion of the first fourth joint angles to simplify and reduce the variables in the new position equation of the 7R robot arm. Therefore, the method is still valid and applicable for those types of wrists in [19,20,21].

The right side of Equations (28) and (32) is related to the wrist part of the robot arm wrist. Let l5 = l6=0; thus, the right side of the equation equals zero, and the simplified part of the wrist vanishes in the new position equation. As a result, Equation (44) becomes equivalent to the position equation of the robot arm with a spherical wrist, as in Equation (7). Therefore, the equation resulting from the offsets of the wrist and the position equation depends on the τ1,τ2,τ3 joints. This result demonstrates that the proposed method is applicable to both spherical and non-spherical wrists in 6-DOF robot arms (with revolute or prismatic joints, for prismatic joints; θl=0 and thus Ql=1) as well as to 3-DOF planar robot arms.

From the aforementioned, it is evident that the proposed method is universal and does not consume computational time to obtain approximate and actual solutions, unlike previous approaches reported in the literature that artificially simplify the wrist’s structure. However, the virtual wrist method for obtaining initial solutions is useful for obtaining unique solutions and optimizing the time cost for iterative algorithms sensitive to the initial value.

4.4. The Inverse Kinematics Solution Algorithm

The main steps for the proposed IK solution algorithm are as follows:

Unify the variables from sin/cos to tangent half angles by converting the rotation matrix into a tangent rotation matrix and the desired orientation into a tangent quaternion.

Separate the wrist’s variables from the position variables, then obtain the structural parameters matrix (C.).

Simplify the kinematic position equations by substituting the wrist variables with the position variables.

Use random or home joint angles as inputs to the simplified position equations to obtain an initial solution, if none is available.

Calculate the position increment ep and obtain the synthetically generated errors.

If the synthetic error is within range, jump to step (viii); otherwise, compute Δθ determine the updated values for the three joint variables, and substitute them into the modified position equation for the next iteration.

Repeat steps (iv∼vi) until the synthetic error reaches the preset criteria (ε) or the number of iterations reaches the maximum set number.

Obtain the wrist joint variables from Equation (47) after the IK solution of the position joint variables is obtained. The algorithm’s pseudocode is detailed below Algorithm 1:

Algorithm 1 The IK pseudocode of the algorithm.

1:. Inputs: Structure parameters (vl,ll), Desire position

            and Orientation vectors rld0,qld0; Tolerance ε;

2:. Output:   Robot arm joint angles θk

3:.              Converting Rl0Ql0,ql0Tl0

4:.              Initialize   τ1,τ2,,τk3C.ij·Tl0       

5:.              Psimp=rls0

6:.  Begin i=k                 % k = (n3); n = n-DOF.

7:.            rls0(θkinitial)=rls0(θk(i))

8:.            rls0rld0=ep

9:.       while ep>ε       do

10:.               θk(i)=θk(i)+J+.ep

11:.                i=i+1

12:.                rls0(θk(i))rld0=ep

13:.                repeat steps 7∼8

14:.          end while

15:.            θ=θk       % Obtain all position joints.

16:.   return θ=θn%Obtain wrist joints from Equation (47)

17:.    end

The first three angles are calculated using the algorithm by adjusting the position error limitation. Then, the orientation equations in Equation (47) are updated with the results to obtain all solutions.

5. Numerical Experiments, Simulations, and Practical Applications

To verify the accuracy and efficiency of the proposed method, numerical experiments and simulations were performed on two types of robot arms. The method was initially evaluated on a 5R robot arm and then on a 6R polishing robot arm (UR-10). The proposed Algorithm 1 was compared with the NR and DLS algorithms. Simulations and practical experiments were then conducted for trajectory planning of the UR-10, and the results were analyzed. The experiments and programming were performed on a computer equipped with an Intel Core™ i5-7400 3.20 GHz processor with 8 GB RAM.

5.1. Performance Analysis of a Proposed IK Algorithm for a 5R Robot Arm

The IK solution algorithm was implemented first on the 5R robot without any tool attached to the EE. The robot arm’s geometric configuration and structural parameters are presented in Figure 2 and Table 2, respectively.

The desired position r5d0=[0.4276, 0.1514, 0.5585,]T and the desired orientation q4d0=[0.0255, 0.9379, 0.2807, 0.2023,]T were taken as the desired pose for obtaining the IK solutions. Initially, zero joint angles θk=[0, 0, 0, 0, 0] were used to obtain the variation between the robot arm’s home pose and the given EE pose through the FK equations. Then, 1000 joint angle sets were randomly generated within the range of 180 to 180 to test and evaluate the precision and efficiency of the algorithm. The tolerance (i.e., convergence) was set to 1 × 1015, 1 × 1016, and 1 × 1017, where the computation time depends on the tolerance and initial solutions of the first joint angles. This approach is expected because the initial solution will require fewer iterations, making the algorithm less time-consuming and more stable. In this test, the average tolerance for the method was set to 1 × 1015 with the initial (guess) solution chosen randomly.

Figure 3 and Figure 4 show the position error and computation time for all the tests, respectively. The position error remained within the tolerance set for the experiment, except for tests 418, 660, and 704. Furthermore, the computation time of the algorithm did not exceed 0.011 s, except in three tests only, where 92.7% of the tests took less than 0.002 s to obtain the IK solution. Table 3 summarizes the statistical characteristics (minimum, maximum, mean, and standard deviation) of the joint-angle errors for each joint of the 5R robot arm computed using the IK solution algorithm.

5.2. Solving Inverse Kinematics of the 6R Industrial Robot Arm UR10

The geometry of the 6R UR-10 robot arm with an attached tool and its structural parameters are presented in Figure 5 and Table 4, respectively. Similarly, the six joint angles θk=[42, 44, 47, 70, 81, 20] are considered to obtain the desired pose configuration of the EE r6d0 and q5d0 through the FK equations. The remaining IK solution angles are then determined using the proposed algorithm. The eight sets of joint variables calculated using the proposed IK algorithm are shown in Table 5.

Figure 6 and Figure 7 show the position and orientation errors; the synthetic error is 1.8 × 1014 m and 17.75 × 106 deg, for position and orientation, respectively. The absolute difference values between the obtained joints angles and the test joint angles are less than 0.0001, except for in 3.7% of tests. The minimum, maximum, mean, and standard deviation of joint-angle errors of the IK solution for the 6R (UR-10) robot arm are listed in Table 6.

The computational times and the number of iterations of the algorithm are shown in Figure 8 and Figure 9, respectively. When the convergence accuracy is set to 1 × 1015, the algorithm reaches the maximum number of iterations in only 10 tests. The computational time of the algorithm exceeds 4.5 × 103 s only in a few tests, as shown in Figure 8, where 6.6% of the tests are in the range between 3.2 × 103 and 4.3 × 103 seconds, and the rest of the solution results are less than 0.0005 s.

5.3. Comparative Analysis of Inverse Kinematics Methods

5.3.1. Comparing with NR and DLS Algorithm UR-10

To evaluate the effectiveness of wrist variable reduction in enhancing the precision, computational speed, and overall efficiency of IK solutions, a comparative analysis was conducted using the NR and DLS algorithms on the UR-10 robot arm. These algorithms are commonly used for solving IK problems through iterative numerical approaches [11,20,21].

To apply these algorithms, the full-size (6×6) Jacobian matrix must first be obtained. The Jacobian matrix of the UR-10 robot arm is expressed as

(49)J6=JpJw=df1dθ1df1dθ2...df1dθ6df2dθ1df2dθ2...df2dθ6df6dθ1df6dθ2...df6dθ6.

where Jp, Jw represent the linear and angular components of the Jacobian matrix, respectively; and fi, θi denote the independent equation functions and joint variables, respectively. The UR-10 robot arm has six unknown joint variables; therefore, six independent equations are required fi=0 and i = 1, 2, …, 6. These equations can be obtained from Equations (5) and (8), where f1, f2, f3, f4, f5, and f6 are given in Appendix A.

The test poses were defined by four sets of joint angles, as listed in Table 7. In each test, the convergence tolerance was set to 0.001 mm. The initial solutions for the NR and DLS methods were used to compute the IK solutions for test poses I–III. The final test, corresponding to pose IV, was performed without an initial solution to evaluate the influence of the initial guess on algorithm performance. The NR algorithm failed to converge for test pose IV when the initial guess was θinitial=[0,0,0,0,0,0], as shown in Table 8.

The position and orientation errors, computational time, and number of iterations required for convergence were used as evaluation metrics to compare the NR, DLS, and proposed algorithms, as summarized in Table 9. The results demonstrate that the NR and DLS algorithms yield significantly higher orientation errors compared to the proposed method, which consistently achieves zero orientation error. In the proposed Algorithm 1, the orientation errors are inherently coupled with the positional joint variables, leading to improved accuracy and stability.

As shown in Table 8 and Table 9, the proposed algorithm achieves lower computational cost and smaller positional error than both the NR and DLS algorithms. This improvement primarily results from the wrist-variable reduction technique, which maintains a fixed number of rows in the Jacobian matrix. This configuration enhances numerical stability and reduces computational complexity. Consequently, the proposed approach offers a clear advantage over existing methods in the literature [19,20,21], which rely on artificial simplifications of the kinematic equations.

It is clear that the initial solution affects the performance of the algorithms in terms of the computation time required to achieve accurate results. Inappropriate initial solutions may cause the NR algorithm to fail, as it is more sensitive to the initial joint angles. However, the proposed algorithm exhibits high stability and insensitivity to the initial joint angles, particularly those of the wrist, because these variables are fully independent, as shown in Equation (47).

5.3.2. Comparative Performance of Traditional and Proposed Inverse Kinematics Methods

The proposed IK method demonstrates superior accuracy and stability compared to the approaches in the literature under identical testing conditions. Figure 10 shows the comparative analysis of synthetic error distribution during IK convergence for the traditional method and the proposed algorithm.

Both methods were tested under identical conditions using 1000 joint angle sets with a convergence tolerance of 1 × 106. The black solid line represents the synthetic error (ePose), the red dashed line shows the position error norm (ep), and the blue dotted line indicates the orientation error norm (eang). The proposed method achieves significantly lower position errors (0.0–0.6 × 106) and orientation errors (0.0–0.4 × 106) in inter-peak regions compared to the method in references [19,20,21], which shows (0.0–1 × 106) for both position and orientation errors, while maintaining comparable performance at critical peaks. This enhanced stability and reduced error are also reflected in the mathematical formulation of our method Equation (45) without orientation error and Equation (9), which, including both position and orientation errors, demonstrates superior convergence behavior and numerical robustness across all tests. The results show that our method achieves fewer position and orientation errors under equivalent conditions, confirming its higher precision and computational efficiency.

5.4. Simulation and Practical Application of Trajectory Planning

5.4.1. Simulation

To further demonstrate the method’s practicability, it is applied to track a trajectory planned in Cartesian coordinates. The algorithm is first applied in simulation to solve the IK for a set of EE poses forming a continuous trajectory and to perform polishing tasks using the UR-10 robot arm. It is then implemented in real-time operation.

The 6-DOF (UR-10) robot and the polishing task are shown in Figure 11. The trajectory of the EE is first taught in the X–Y plane on the surface of the workpiece using RoboDK software (RoboDK Inc., Montreal, QC, Canada; version 5.9.0). The motion of the robot arm’s EE begins at the initial pose (Pose I) listed in Table 7, then it follows the trajectory defined by the subsequent poses, and finally returns to the initial pose. The variations of the six joint angles along the test trajectory are presented in Figure 12.

The position of the robot’s EE keeps changing while the orientation remains constant, as shown in Table 10, which demonstrates the four points (targets) of the corners of the trajectory. Note that only the X and Y axes change between the points, while the Z-axis is perpendicular to the polishing workpiece.

Through the simulation function of Robo-DK, 700 joint angle sets are selected as test samples for trajectory, of which 190 joint sets are used for the two horizontal paths and 160 joint sets for vertical polishing paths. The IK solution of the four end poses is firstly obtained by giving the home position’s joint angles as initial input.

Subsequently, as the joint angles of adjacent EE positions do not vary significantly, the remaining IK solutions are obtained automatically. In this process, the algorithm uses the IK solution set of the previous point as the initial joint variable input for the next point along the path, which effectively reduces computation time and improves precision. The discontinuous motion case is illustrated in Figure 13, where the maximum joint angle differences appear at sequence numbers (0, 197, 364, 543). These points correspond to corners in the path where the EE motion changes from a horizontal to a vertical direction.

In contrast, when the path is followed continuously from the first point to the endpoint, the differences in joint angles are significantly reduced. This occurs because the difference in the joint angles compared with the previous IK solution of end poses is very small between consecutive points, and the errors are proportional to the distance between successive points along the path. Figure 14 presents the joint angle differences for the continuous IK solution. The relatively large peak observed at the beginning (angle sets 1∼11) results from the initial transition between the robot’s home configuration and the first point of the path, where the IK algorithm has not yet adapted to the motion direction. After this initial adjustment, the joint angle differences stabilize and remain constant throughout the path in continuous solution mode, and the motion duration is set to 35 s. In a real robotic implementation, such large initial variations would not occur, as motion planning and trajectory interpolation typically ensure a smooth transition from the home position to the start of the path, which will be discussed in the following section.

5.4.2. Practical Application

To evaluate the performance of the proposed IK algorithm, the experimental parameters were first adjusted using a general elliptical trajectory path. After this initial validation, the method was then applied to the trajectory defined by the selected points in Table 10, to check the consistently with the simulation results presented in section above Section 5.4.1.

The experiment was conducted with a UR10 robot arm for trajectory planning of the real polishing process, using the polishing tool on a flat surface, aiming to verify the validity of the proposed method in practice. The test setup included a UR10 robot arm, an industrial computer that contains the software systems, a UR-10 control unit, a six-axis force sensor type XLH93003ACN with 1000 N in the Z direction, aluminum workpiece material, and a pneumatic polishing tool (type APT-127N). The reference command trajectory was transmitted to the robot controller via C++17 using GCC 13.2.0.

Figure 15 illustrates the trajectory-tracking validation by comparing the planned (yellow) and actual (red) EE paths. The close overlap between the two demonstrates the accuracy of the experimental setup in maintaining precise EE motion during continuous Cartesian-space operation, thereby confirming its suitability for real-time robotic tasks.

For further validation and to ensure a clear comparison between the simulation and experimental results, the robot was set to move 50 mm in the negative Z-direction toward the flat surface (XY plane) and then maintain a constant orientation throughout all trajectories defined by the four poses in Table 10. Then, the polishing path moved 38 cm on the surface in the X-direction and 16 cm in the Y-direction, according to the taught trajectory in the above simulation in Figure 16.

Furthermore, Figure 17 and Figure 18 present the orientation error and the joint angle differences in the experiment for the continuous polishing task along the path. The experiment was repeatedly executed to obtain a reasonable estimation of the IK solution. The computation time ranged from 16 to 40 s, which meets the real-time requirement of the robot arm. The orientation was planned to remain constant within a tolerance of (26.5×106) deg. According to the practical polishing test IK results, we found that the orientation error was higher than that in the first experimental scheme discussed in Section 5.4.1 and the one obtained by simulation. The slight orientation oscillations among the planned path, the simulation, and the practical polishing track, shown in Figure 17, are caused by surface stiffness due to protrusions and cavities, in addition to vibrations induced by the use of a dynamic polishing tool during the experimental tests.

In contrast, experimental polishing tests showed a slight difference between the joint angles computed by the algorithm and those from simulations, as shown in Figure 18. This is due to the neglect of those factors previously mentioned in the simulation environment tests. These results also showed that the difference in rotation of joints 2, 3, and 4 affects both the position and orientation of the EE. As mentioned earlier, the position joints significantly affect the computation of orientation angle solutions in our technique for simplifying Equation (47). The combined error primarily accumulates in joint 2 and joint 3, with peak error differences appearing only in sequence numbers 20 and 160. However, the difference in joint angles between the simulation and experimental results in real time does not exceed (±55.6×108) deg. Therefore, these results are considered satisfactory and within the limits of the experimental testing setup. These results confirm the algorithm’s robustness in maintaining the poses accurately throughout the continuous polishing path.

In general, the proposed algorithm effectively and efficiently solves the IK problems for continuous trajectories. The results are also consistent between simulation and practical implementation. It is worth noting that approaches for simplifying and reducing the complexity of kinematic formulas are applicable to more than just 6R robot arms. The 7R and 8R robotic arms can also use a similar integration method to eliminate the wrist joint variables from robot arm equations and reduce the computational cost of the kinematic equations. The methodology can also be extended to systems with more than 9-DOF, specifically for multi-axis systems. However, finding unique solutions for systems with more than 9-DOF is challenging because they require a one-dimensional algorithm. The proposed method has not been tested near singular configurations. Nevertheless, no significant effects are expected, as the approach relies on the integration of DTM, quaternion, and position vectors in a univariate form under the natural coordinate system.

6. Conclusions

A new method was presented to describe kinematic equations in a simple form by integrating the rotation matrix and quaternion, providing a novel formula for efficient and accurate kinematic equations with simplified constraints. First, the simplified FK equations for the 6R robot arm were obtained analytically by substituting the wrist joint variables into the modified position vector equation. Then, the accurate IK solution was obtained iteratively.

The 6R (UR-10) robot arm with an offset wrist was used to illustrate the kinematic modeling and mathematical processes associated with this method. In the first test, the solutions were obtained for a given EE configuration where the position absolute error was less than 1015 m. In the second test, the algorithm’s performance for polishing tasks was evaluated in a practical application to assess its accuracy and efficiency in real-time operation. The proposed method reduces computation complexity, which requires only the position variables to obtain the desired position in FK. Moreover, the algorithm converges fast because it does not require debugging of any hyper-parameters, and it is less sensitive to the initial solution. Furthermore, the algorithm is unaffected by workspace reduction or the lack of the IK solution due to structural simplifications, as seen in other methods, which artificially simplify offset mechanisms for obtaining solutions.

The proposed methodology holds strong potential for advancing robotic kinematic modeling and enhancing polynomial-based numerical iterative algorithms. It may also stimulate further research in robotic dynamics and control, particularly in addressing the limitations observed in the slight variations between planned simulations and real-time experimental results.

Author Contributions

The following list outlines the authors’ contributions to this paper: Conceptualization, software, writing—original draft preparation, A.A.; formal analysis, Y.Y.; writing—review and editing, H.W., G.I.Y.M. and A.A.; visualization, validation, supervision, H.J. All authors have read and agreed to the published version of the manuscript.

Informed Consent Statement

Informed consent was obtained from all subjects involved in this study.

Data Availability Statement

Data are contained within the article or Supplementary Materials.

Acknowledgments

The authors would like to thank Wuxi University (WXU) and Nanjing University of Aeronautics and Astronautics (NUAA) for their support. Special thanks are also extended to China Electronics Technology Group Corporation for their valuable assistance.

Conflicts of Interest

The authors declare no conflicts of interest.

Nomenclature and Abbreviations

Nomenclature

Symbols       Definition Symbols       Definition Symbols          Definition
      ll Length and offset of link       vl Axis vector of link l       v^l 3×3 skew- symmetric matrix of (vl)
      Rl Rotation matrix       τl Quaternion vector part       C.ij Structural parameter matrix
      Tl Tangent quaternion       τl Tangent half-angle       τl0 Modulus squares =1+(τl0)2
      τ.l Scalar part of quaternion       eang Orientation error       ep Position error
      rl Position vector       rnd0 Desired position       Tnd0 Desired attitude
      I 3×3 identity matrix       03 3×1 zero vector       E45 Matrix of adjacent wrist axes

Abbreviations

DTM Direction tangent matrix
DCM Direction cosine matrix
DOF Degrees of freedom
IK Inverse kinematic
FK Forward kinematic
EE End effector
INS Initial solution

Footnotes

Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Figures and Tables

Figure 1 Structure of decoupled robot arm. (a) Euler’s wrist; (b) offset wrist.

View Image -

Figure 2 The schematic diagram and coordinate frames of the 5R robot arm model (home position).

View Image -

Figure 3 Performance of an algorithm for a 5R robot arm in position errors of the IK solutions.

View Image -

Figure 4 Performance of the IK solution algorithm on a 1000 angle set for a 5R robot arm: number of iterations.

View Image -

Figure 5 The structure and coordinate frames of the 6R UR-10 robot arm.

View Image -

Figure 6 Performance of an algorithm for 6R (UR-10) robot arm in position errors of the IK solutions.

View Image -

Figure 7 Performance of an algorithm for 6R (UR-10) robot arm in orientation errors of the IK solutions.

View Image -

Figure 8 Performance of the IK solution algorithm on a 1000 angle set for 6R (UR-10) robot arm: calculation time.

View Image -

Figure 9 Performance of the IK solution algorithm on a 1000 angle set for 6R (UR-10) robot arm: number of iterations.

View Image -

Figure 10 Comparative analysis of synthetic error distribution during inverse kinematics convergence: (a) traditional method; (b) proposed algorithm.

View Image -

Figure 11 (af) Motion trajectory showing the four main poses used to test the polishing trajectory of the UR-10 robot arm.

View Image -

Figure 12 Joint angles of each end pose sample on testing trajectory coming from RobotDK.

View Image -

Figure 13 Joint angle differences for the discontinuous IK solution along the path.

View Image -

Figure 14 Joint angle differences for the continuous IK solution along the path.

View Image -

Figure 15 Experimental setup for trajectory planning. (a) Experimental setup; (b) comparison of planned and actual trajectories.

View Image -

Figure 16 (ad) Practical experiment with the UR-10 robot arm and polishing tool to evaluate IK solutions for a continuous trajectory.

View Image -

Figure 17 Comparison of orientation errors between the planned, simulation, and practical polishing trajectories.

View Image -

Figure 18 Joint angle differences between the actual and experimental continuous polishing track.

View Image -

The properties and mathematical operation of a tangent quaternion.

Operation Definition
Scalar multiplication c · T l = c · τ l , c · τ . l T
Unit quaternion T l = 0 3 , τ . l T
Direction quaternion T l = τ l , 0 T
Conjugate and inverse T l * = T l 1 = τ l , τ . l T
Multiplication T l 2 0 = T l 0 T l 2 l = τ . l · τ l 2 + τ . l 2 · τ l + τ l · τ l 2 τ . l . τ . l 2 τ l . τ l 2 4 × 1

Structural parameters of a 5-DOF robot arm.

Axes Axis Vector Position Vector (m)
No. v x v y v z l x l y l z
1 0 0 1 0.0 0.0 0.1833
2 0 1 0 0.7373 0.0 0.0
3 0 1 0 0.0 −0.1723 0.3878
4 0 1 0 0.1155 0.0 0.0
5 0 0 1 0.0 0.0995 0.0

Statistical analysis of error of inverse kinematic solutions of each joint of the 5R robot arm (deg).

Statistical Analysis Joint 1 Joint 2 Joint 3 Joint 4 Joint 5
Min 3.423 × 10 16 9.91 × 10 16 2.69 × 10 15 2.43 × 10 16 1.47 × 10 17
Max 2.158 × 10 6 2.97 × 10 6 7.18 × 10 6 6.79 × 10 6 5.62 × 10 6
Mean 4.009 × 10 8 1.35 × 10 7 1.79 × 10 7 1.87 × 10 7 1.39 × 10 7
Std 1.504 × 10 7 4.02 × 10 7 6.011 × 10 7 6.69 × 10 7 5.25 × 10 7

Structural parameters of a 6-DOF robot arm.

Axes Axis Vector       Position Vector (m)
No. v x v y v z l x l y l z
1 0 0 1 0.0 0.0 0.089
2 0 −1 0 0.425 0.0 0.0
3 0 −1 0 0.392 0.0 0.0
4 0 −1 0 0.0 −0.109 0.0
5 0 0 1 0.0 0.0 0.094
6 0 −1 0 0.0 −0.161 0.0

The IK solutions of the UR-10 robot arm.

IK Solution Joint Angles (Deg)
No. θ 1 θ 2 θ 3 θ 4 θ 5 θ 6
1 −42.1383 135.8865 107.9325 −112.77 73.04824 6.527121
2 −42.1383 −126.811 −107.932 5.7919 73.04824 6.527121
3 −42.1383 176.9473 −46.6189 −272.608 −73.0485 −173.564
4 −42.1383 44.48952 46.61868 −70.3628 81.60569 −20.978
5 100.7149 −139.901 −107.319 137.4768 −73.0485 −173.564
6 100.7149 307.6839 107.3192 −171.804 −81.6059 −20.978
7 100.7149 3.111478 −47.4185 91.2056 −81.6059 159.1134
8 100.7149 319.2229 47.41836 −40.258 81.60569 159.1134

Statistical analysis of inverse kinematic solution errors for each joint of the UR-10 robot arm (deg).

Statistical Analysis Joint 1 Joint 2 Joint 3 Joint 4 Joint 5 Joint 6
Min 8.8816 × 10 13 7.09 × 10 13 2.31 × 10 12 9.39 × 10 14 2.97 × 10 13 1.15 × 10 12
Max 1.469 × 10 5 4.49 × 10 6 1.13 × 10 6 8.92 × 10 7 1.95 × 10 6 1.44 × 10 6
Mean 1.854 × 10 8 7.72 × 10 9 3.12 × 10 9 2.34 × 10 9 3.55 × 10 9 3.35 × 10 9
Std 4.724 × 10 7 1.55 × 10 7 4.53 × 10 8 3.87 × 10 8 6.59 × 10 8 5.43 × 10 8

Test datasets in joint space (deg).

Poses Joint 1 Joint 2 Joint 3 Joint 4 Joint 5 Joint 6
Pose I 13.81 129.48 86.10 46.10 87.63 13.61
Pose II 43.18 135.67 89.89 51.74 96.80 42.74
Pose III 55.09 117.31 114.43 44.01 98.16 54.68
Pose IV 18.37 114.97 114.53 49.97 86.87 18.11

Joint angle solutions and comparison of the proposed method (PM) with NR and DLS algorithms.

Poses Method Time (s) IK Solutions of the Joint Angles
θ 1 θ 2 θ 3 θ 4 θ 5 θ 6
Pose I INS 0.0 −18.05 −115.97 −112.57 −50.94 86.93 −17.8
NR 0.02 −13.81 −129.48 −86.1 −64.1 87.63 −13.61
DLS 0.187 13.18 −132.41 −87.9 −58.25 91.98 13.08
PM 0.002 −13.81 −129.48 −86.10 −46.10 87.63 −13.61
Pose II INS 0.0 45.08 −132.73 −93.82 −50.51 97.02 44.65
NR 0.035 44.13 −134.2 −91.86 −51.12 96.91 43.7
DLS 0.5 44.61 −133.46 −92.84 −50.82 96.97 44.18
PM 0.0017 43.18 −135.67 −89.89 −51.74 96.80 42.74
Pose III INS 0.0 53.66 −119.51 −111.48 −44.94 98 53.25
NR 0.0065 54.14 −118.78 −112.46 −44.63 98.05 53.73
DLS 0.265 50.11 −116.74 −114.53 −44.76 97.4 56.28
PM 0.0036 55.09 −117.31 −114.43 −44.01 98.16 54.68
Pose IV INS 0.0 0 0 0 0 0 0
NR - - - - - - -
DLS 2.455 18.69 251.08 −115.93 −55.18 273.7 78.2
PM 0.0005 −18.37 −114.97 −114.53 −49.97 86.87 −18.11

Performance comparison of IK algorithms for robot arm: accuracy, convergence, and computational time.

Algorithm Position Orientation Error Computation Avg. Iterations Error Remarks
Error (mm) Error (deg) Time (s) to Converge Tolerance (m)
NR 0.002207 0.04882 0.0205 6–10 10 6 Fast & Unstable
DLS 0.004312 0.20903 0.8518 8–12 Stable & Slower
PM 0.000009 0.000002 0.0015 2–4 Fast & stable

Desired position and orientation at EE frame.

Poses Desired Position Desired Orientation
[ P x , P y , P z ] T [ q x , q y , q z , q 0 ] T
Pose I [ 0.3723 , 0.0035 , 0.0053 ] T [ 0.4547 , 0.4547 , 0.4547 , 0.4547 ] T
Pose II [ 0.5221 , 0.0121 , 0.0184 ] T [ 0.4547 , 0.4547 , 0.4547 , 0.4547 ] T
Pose III [ 0.2884 , 0.4148 , 0.0683 ] T [ 0.4547 , 0.4547 , 0.4547 , 0.4547 ] T
Pose IV [ 0.1212 , 0.3446 , 0.0182 ] T [ 0.4547 , 0.4547 , 0.4547 , 0.4547 ] T

Supplementary Materials

The following supporting information can be downloaded at: https://www.mdpi.com/article/10.3390/machines13121073/s1. Video S1: Experimental setup showing Elliptical path trajectory (Planned vs. Actual). Video S2: Practical demonstration of IK solutions for continuous polishing trajectory on UR-10 robot arm.

Appendix A

The linear Jacobian Jp is a (3 ×n) matrix, and (n) denotes the DOF of the robot arm, represented as follows:Jp=df1dθidf2dθidf3dθi where

f1=l2xc1c2+l3xc1c23+l4ys1+l5zc1s234+l6y(s1c5c1s5c234),f2=l2xs1c2+l3xs1c23l4yc1+l5zc1s234l6y(c1c5+s1s5c234),f3=l2xs2+l3xs23+l1zl5zc234l6ys5s234andsi=sin(θi),ci=cos(θi),sij=sin(θi+θj),cij=cos(θi+θj),1i,j6

The angular Jacobian Jw is (3 ×n) matrix is donated asJw=R10.v1R20.v2R60.v6 where i = 1,2... 6 and Ri0.vi is the transformation rotation matrix, which vi represents the direction of the joint axis rotation and it give the 3-rd column of Jw [16].

References

1. Haslwanter, T. 3D Kinematics; Springer Nature: Cham, Switzerland, 2018; pp. 15-191. [DOI: https://dx.doi.org/10.1007/978-3-319-75277-8]

2. Angeles, J. Fundamentals of Robotic Mechanical Systems: Theory, Methods, and Algorithms; Springer: Berlin/Heidelberg, Germany, 2014; [DOI: https://dx.doi.org/10.1007/978-3-319-01851-5]

3. Abdolraheem, K.; Yang, J.; Xiao, L. Nmf-dunet: Nonnegative matrix factorization inspired deep unrolling networks for hyperspectral and multispectral image fusion. IEEE J. Sel. Appl. Earth Obs. Remote Sens.; 2022; 15, pp. 5704-5720. [DOI: https://dx.doi.org/10.1109/JSTARS.2022.3189551]

4. Damos, M.A.; Zhu, J.; Li, W.; Khalifa, E.; Hassan, A.; Elhabob, R.; Hm, A.; Ei, E. Enhancing the K-Means Algorithm through a Genetic Algorithm Based on Survey and Social Media Tourism Objectives for Tourism Path Recommendations. ISPRS Int. J. Geo-Inf.; 2024; 13, 40. [DOI: https://dx.doi.org/10.3390/ijgi13020040]

5. Aristidou, A.; Lasenby, J. Inverse Kinematics: A Review of Existing Techniques and Introduction of a New Fast Iterative Solver. 2009; Available online: https://www.researchgate.net/profile/Andreas-Aristidou/publication/273166356_Inverse_Kinematics_a_review_of_existing_techniques_and_introduction_of_a_new_fast_iterative_solver/links/54faeca10cf20b0d2cb8782b/Inverse-Kinematics-a-review-of-existing-techniques-and-introduction-of-a-new-fast-iterative-solver.pdf (accessed on 20 May 2025).

6. Hjorth, S.; Chrysostomou, D. Human-robot collaboration in industrial environments: A literature review on non-destructive disassembly. Robot. Comput.-Integr. Manuf.; 2022; 73, 102208. [DOI: https://dx.doi.org/10.1016/j.rcim.2021.102208]

7. Pieper, D.L. The Kinematics of Manipulators Under Computer Control. Ph.D. Thesis; Stanford University: Stanford, CA, USA, 1969.

8. Ahmed, A.; Yu, M.; Chen, F. Inverse kinematic solution of 6-dof robot-arm based on dual quaternions and axis invariant methods. Arab. J. Sci. Eng.; 2022; 47, pp. 15915-15930. [DOI: https://dx.doi.org/10.1007/s13369-022-06794-6]

9. Hentout, A.; Aouache, M.; Maoudj, A.; Akli, I. Human-robot interaction in industrial collaborative robotics: A literature review of the decade 2008–2017. Adv. Robot.; 2019; 33, pp. 764-799. [DOI: https://dx.doi.org/10.1080/01691864.2019.1636714]

10. Abbes, M.; Poisson, G. Geometric Approach for Inverse Kinematics of the FANUC CRX Collaborative Robot. Robotics; 2024; 13, 91. [DOI: https://dx.doi.org/10.3390/robotics13060091]

11. Kucuk, S.; Bingul, Z. Inverse kinematics solutions for industrial robot manipulators with offset wrists. Appl. Math. Model.; 2014; 38, pp. 1983-1999. [DOI: https://dx.doi.org/10.1016/j.apm.2013.10.014]

12. Raghavan, M.; Roth, B. Inverse Kinematics of the General 6R Manipulator and Related Linkages. ASME J. Mech. Des.; 1993; 115, pp. 502-508. [DOI: https://dx.doi.org/10.1115/1.2919218]

13. Vito, D.D.; Natale, C.; Antonelli, G. A comparison of damped least squares algorithms for inverse kinematics of robot manipulators. IFAC-PapersOnLine; 2017; 50, pp. 6869-6874. [DOI: https://dx.doi.org/10.1016/j.ifacol.2017.08.1209]

14. Sugihara, T. Solvability-unconcerned inverse kinematics by the levenberg-marquardt method. IEEE Trans. Robot.; 2011; 27, pp. 984-991. [DOI: https://dx.doi.org/10.1109/TRO.2011.2148230]

15. Funda, J.; Taylor, R.H.; Paul, R.P. On homogeneous transforms, quaternions, and computational efficiency. IEEE Trans. Robot. Autom.; 1990; 6, pp. 382-388. [DOI: https://dx.doi.org/10.1109/70.56658]

16. Corke, P. Robotics, Vision and Control: Fundamental Algorithms in MATLAB® Second, Completely Revised; Springer: Berlin/Heidelberg, Germany, 2017; Volume 118, [DOI: https://dx.doi.org/10.1007/978-3-642-20144-8]

17. Guzman-Gimenez, J.; Valera Fernandez, A.; Mata Amela, V.; Díaz-Rodríguez, M.Á. Automatic selection of the Gröbner Basis’ monomial order employed for the synthesis of the inverse kinematic model of non-redundant open-chain robotic systems. Mech. Based Des. Struct. Mach.; 2023; 51, pp. 2458-2480. [DOI: https://dx.doi.org/10.1080/15397734.2021.1899829]

18. Lee, C.; Ziegler, M. Geometric approach in solving inverse kinematics of puma robots. IEEE Trans. Aerosp. Electron. Syst.; 1984; 6, pp. 695-706. [DOI: https://dx.doi.org/10.1109/TAES.1984.310452]

19. Wu, L.; Yang, X.; Miao, D.; Xie, Y.; Chen, K. Inverse kinematics of a class of 7r 6-dof robots with non-spherical wrist. Proceedings of the IEEE International Conference on Mechatronics and Automation; Takamatsu, Japan, 4–7 August 2013; pp. 69-74. [DOI: https://dx.doi.org/10.1109/ICMA.2013.6617895]

20. Wang, X.; Zhang, D.; Zhao, C. Inverse kinematics of a 7r 6-dof robot with nonspherical wrist based on transformation into the 6r robot. Math. Probl. Eng.; 2017; 2017, 2074137. [DOI: https://dx.doi.org/10.1155/2017/2074137]

21. Zhou, X.; Xian, Y.; Chen, Y.; Chen, T.; Yang, L.; Chen, S.; Huang, J. An improved inverse kinematics solution for 6-dof robot manipulators with offset wrists. Robotica; 2022; 40, pp. 2275-2294. [DOI: https://dx.doi.org/10.1017/S0263574721001648]

22. Toz, M. Chaos-based vortex search algorithm for solving inverse kinematics problem of serial robot manipulators with offset wrist. Appl. Soft Comput.; 2020; 89, 106074. [DOI: https://dx.doi.org/10.1016/j.asoc.2020.106074]

23. Li, J.; Yu, H.; Shen, N.; Zhong, Z.; Lu, Y.; Fan, J. A novel inverse kinematics method for 6-dof robots with non-spherical wrist. Mech. Mach. Theory; 2021; 57, 104180. [DOI: https://dx.doi.org/10.1016/j.mechmachtheory.2020.104180]

24. Dai, J.S. Euler-rodrigues formula variations, quaternion conjugation and intrinsic connections. Mech. Mach. Theory; 2015; 92, pp. 144-152. [DOI: https://dx.doi.org/10.1016/j.mechmachtheory.2015.03.004]

25. Xu, J.; Song, K.; He, Y.; Dong, Z.; Yan, Y. Inverse kinematics for 6-dof serial manipulators with offset or reduced wrists via a hierarchical iterative algorithm. IEEE Access; 2018; 6, pp. 52899-52910. [DOI: https://dx.doi.org/10.1109/ACCESS.2018.2870332]

26. Ahmed, A.; Ju, H.; Yang, Y.; Xu, H. An Improved Unit Quaternion for Attitude Alignment and Inverse Kinematic Solution of the Robot Arm Wrist. Machines; 2023; 11, 669. [DOI: https://dx.doi.org/10.3390/machines11070669]

27. Wahballa, H.; Ahmed, A.; Duan, J.; Chen, X.; Weining, L. Force tracking in robotic control systems using an online work object stiffness hybrid impedance PI control approach. Results Eng.; 2025; 26, 105520. [DOI: https://dx.doi.org/10.1016/j.rineng.2025.105520]

28. Tatar, A.B. W-Leg Jumping Robot: Mechanical Design, Dynamical Analysis and Simulation of Jumping Dual Wheel-Leg Hybrid Robot. Arab. J. Sci. Eng.; 2024; 49, pp. 15463-15481. [DOI: https://dx.doi.org/10.1007/s13369-024-08977-9]

29. Wahballa, H.; Ahmed, A.; Mustafa, G.I.Y.; Gibreel, M.; Weining, L. Robotic Contact on Complex Curved Surfaces Using Adaptive Trajectory Planning Through Precise Force Control. Machines; 2025; 13, 794. [DOI: https://dx.doi.org/10.3390/machines13090794]

30. Gibbs, J.W. Quaternions and vector analysis. Nature; 1893; 48, pp. 364-367. [DOI: https://dx.doi.org/10.1038/048364b0]

© 2025 by the authors. Licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution (CC BY) license (https://creativecommons.org/licenses/by/4.0/). Notwithstanding the ProQuest Terms and Conditions, you may use this content in accordance with the terms of the License.