Next Article in Journal
Fault Detection in Industrial Equipment through Analysis of Time Series Stationarity
Previous Article in Journal
Performance Analysis and Parallel Scalability of Numerical Methods for Fractional-in-Space Diffusion Problems with Adaptive Time Stepping
Previous Article in Special Issue
Application of Evolutionary Computation to the Optimization of Biodiesel Mixtures Using a Nature-Inspired Adaptive Genetic Algorithm
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Inverse Kinematics of Robotic Manipulators Based on Hybrid Differential Evolution and Jacobian Pseudoinverse Approach

by
Jesus Hernandez-Barragan
,
Josue Plascencia-Lopez
,
Michel Lopez-Franco
,
Nancy Arana-Daniel
and
Carlos Lopez-Franco
*
Computer Science Department, University of Guadalajara, 1421 Marcelino Garcia Barragan, Guadalajara 44430, Jalisco, Mexico
*
Author to whom correspondence should be addressed.
Algorithms 2024, 17(10), 454; https://doi.org/10.3390/a17100454
Submission received: 17 August 2024 / Revised: 4 October 2024 / Accepted: 8 October 2024 / Published: 12 October 2024
(This article belongs to the Special Issue Bio-Inspired Algorithms)

Abstract

:
Robot manipulators play a critical role in several industrial applications by providing high precision and accuracy. To perform these tasks, manipulator robots require the effective computation of inverse kinematics. Conventional methods to solve IK often encounter significant challenges, such as singularities, non-linear equations, and poor generalization across different robotic configurations. In this work, we propose a novel approach to solve the inverse kinematics (IK) problem in robotic manipulators using a metaheuristic algorithm enhanced with a Jacobian step. Our method overcomes those limitations by selectively applying the Jacobian step to the differential evolution (DE) algorithm. The effectiveness and versatility of the proposed approach are demonstrated through simulations and real-world experimentation on a 5 DOF KUKA robotic arm.

1. Introduction

Manipulator robots, known for their unparalleled precision, efficiency, and safety, are revolutionizing industries across the globe. These versatile machines are pivotal in space applications, where they service satellites, remove orbital debris, and construct and maintain orbital assets, ensuring the sustainability of our extraterrestrial endeavors [1]. In the automotive industry, robotic manipulators excel in welding tasks, utilizing an electric arc and shielding gas to enhance manufacturing processes [2]. The healthcare sector has also benefited immensely, with robotic arms enabling minimally invasive surgeries that surpass traditional open surgery methods in terms of precision and recovery time [3]. By performing repetitive and hazardous tasks with consistent accuracy, these robotic systems not only improve operational efficiency but also ensure worker safety. Central to their functionality is the complex challenge of solving the inverse kinematics (IK) of the robotic manipulator, a crucial aspect that underpins their application in these diverse fields.
The inverse kinematics problem entails determining the joint variable configuration that corresponds to a specific position and orientation of the end-effector. This task is generally more complex than solving the forward kinematics problem for several reasons [4]:
  • Equations to solve are generally non-linear, making it not always possible to find a closed-form solution.
  • Multiple solutions may exist.
  • Infinite solutions may exist.
  • There might be no admissible solutions.
Conventional numerical methods based on differential kinematics rely on the Jacobian matrix to determine the relationship between joint variables and end-effector positions [5]. However, these methods encounter significant problems due to singularities in the Jacobian matrix, which can lead to undefined or infinite solutions [4,6]. Closed-form methods such as algebraic or geometric methods are commonly used for manipulators with simple geometric structures [7]. Due to these drawbacks, artificial intelligence methods are increasingly utilized to solve the inverse kinematics problem.
In recent years, although to a limited extent, the solution of inverse kinematics has been explored using Artificial Neural Networks (ANNs). Typically, the input to the network is the desired position and orientation of the end-effector and the output is the vector of generalized coordinates, representing the robot’s joint configurations. However, this method faces challenges in generalizing across different kinematic structures or manipulators, as it requires a unique dataset for each specific manipulator. Due to the complexity of the problem, research has been limited to solving it within the three-dimensional Cartesian plane, with the additional necessity of identifying singularity zones [8,9]. Additionally, approaches that account for both position and rotation demand very large datasets and an optimization process for the candidate solution, often utilizing numerical methods such as the Newton–Raphson method [10].
For these reasons, this paper proposes solving the inverse kinematics problem using metaheuristic algorithms. In the past decade, metaheuristic algorithms have emerged as a viable alternative for addressing various challenges in robotics. These algorithms are particularly useful for solving problems that are difficult to tackle with conventional methods or for which no exact solution method exists [11]. In the literature we can find examples of the application of metaheuristic algorithms, such as their use for hyperparameter tuning in both machine learning algorithms and deep neural networks [12], and trajectory tracking optimization [13], as well as in robotic navigation [14].
A review of the state of the art in robotic applications, particularly addressing the inverse kinematics of manipulator robots, is presented in Table 1. This review highlights that differential evolution (DE) and particle swarm optimization (PSO) are the most commonly used metaheuristic algorithms for solving the inverse kinematics problem. Other algorithms, such as Artificial Bee Colony (ABC), bees algorithm (BA), Beta Salp Swarm Algorithm ( β -SSA), Wild Geese Migration Optimization (GMO), Gray Wolf Optimization (GWO), and Firefly Algorithm (FA), have also been implemented. Most studies focus on a single manipulator, with only two cases [15,16] proposing more generalized methods. Typically, these studies address only the position problem, as incorporating orientation significantly increases the complexity of solving the inverse kinematics. Although joint limits are considered in all optimization processes, hard bounding is commonly applied to manage constraints, or candidate solutions are recalculated when they exceed the search space. This approach is necessary because metaheuristic algorithms are not inherently designed to handle constrained problems.
In this paper, we propose a novel method to solve inverse kinematics using a metaheuristic algorithm combined with a Jacobian step. Unlike traditional approaches, the Jacobian step is applied neither in each iteration nor to a subpopulation; it is used selectively when a deadlock is detected, and only to the global best solution. This strategy reduces the implementation complexity of the algorithm. Our method effectively addresses both position and orientation in inverse kinematics, formulating the problem as a constrained optimization task where joint limits are represented as constraints. Since metaheuristic algorithms are not inherently designed for constrained problems, we employ penalty functions to manage these constraints. Our approach is generalizable to redundant robots with n degrees of freedom. The applicability of the algorithm is demonstrated using a 5 DOF KUKA robotic arm, showcasing its effectiveness and versatility.
A comparative study is conducted using the following metaheuristic algorithms: the differential evolution algorithm “DE” proposed by storn et al. in 1997 [29], the particle swarm optimization algorithm “PSO” proposed by Kennedy and Heberhart in 1995 [30], the bees algorithm “BA” proposed by Pham et al. in 2006 [31], the invasive weed optimization algorithm “IWO” proposed by Mehrabian and Lucas in 2006 [32] and the imperialist competitive algorithm “ICA” proposed by Atashpaz-Gargari and Lucas in 2007 [33].

2. Robot Manipulator Kinematics

A robot manipulator consist of a series of links interconnected by joints, forming a kinematic chain. The beginning of the chain is fixed to a base and an end-effector tool is connected to the end of the chain. A joint variable q is defined as q = q 1 q 2 q n T where each joint q j with j = 1 , 2 , , n , where n represents the total DOFs of the manipulator robot [4,34].
A manipulator kinematics model can be described based on the Denavit–Hartenberg convention (DH). Since each joint connects two links, a robot manipulator with n joints will have n + 1 links. In the DH convention, joint i connects link i 1 to link i. Each link i is represented by a homogenous matrix T i i 1 that transforms the frame attached to the link i 1 into the joint link i. The homogeneous matrix T i i 1 is defined as
T i i 1 = cos θ i sin θ i cos α i sin θ i sin α i a i cos θ i sin θ i cos θ i cos α i cos θ i sin α i a i sin θ i 0 sin α i cos α i d i 0 0 0 1 ,
where the parameters θ i , a i , d i , and α i represent the joint angle, link length, link offset, and link twist, respectively. The parameter θ i = q i becomes the joint variable for revolute joints. In contrast, the parameter d i = q i becomes the joint variable for prismatic joints. In both cases, the rest of the parameters remain constant.
The forward kinematics computes the end-effector pose T n 0 given the joint variable q which is
T n 0 q = i = 1 n T i i 1 q i .
The end-effector pose T n 0 contains the position t and orientation R of the tool in the following form:
T n 0 q = R q t q 0 1 = r 11 r 12 r 13 t x r 21 r 22 r 23 t y r 31 r 32 r 33 t z 0 0 0 1 .
The inverse kinematics computes the joint variable q given the end-effector pose T n 0 . The iterative Jacobian pseudoinverse algorithm can solve the inverse kinematics as follows:
q k + 1 = q k + λ J ( q k ) e q k ,
where k represents the current iteration, λ is a positive scalar factor with λ > 0 , J R 6 × n is a Jacobian matrix, and e q k is an error between a desired and current end-effector pose. Moreover, the operation J is the pseudoinverse of J also called the Moore–Penrose inverse. For manipulators of 6 DOF ( n = 6 ), J 1 is rather used. The error e q k is defined as
e q k = e v q k e ω q k T ,
where e v q k is the translation error between the desired t d and current t q k end-effector position. This error is defined as
e v q k = t d t q k .
Moreover, e ω q k is the orientation error between the desired R d and current R q k orientation, that is,
e ω q k = 1 2 R q k 1 0 0 × R d 1 0 0 + R q k 0 1 0 × R d 0 1 0 + R q k 0 0 1 × R d 0 0 1 .
The forward kinematics always provide a solution for any joint variable q . However, inverse kinematics may yield multiple solutions for the same end-effector pose T n 0 . Additionally, the equations involved to solve the inverse kinematics are non-linear, and for that reason it is not always possible to find a closed-form solution. The iterative Jacobian pseudoinverse method is a commonly used approach for solving inverse kinematics. However, this method is prone to singularities, as it necessitates the inversion of a Jacobian matrix that can become rank deficient. To address these limitations, this work proposes solving the inverse kinematics problem using metaheuristic algorithms.

3. Differential Evolution

Differential evolution (DE) is a population-based algorithm employed for global optimization. In this algorithm, population members are called individuals and they represent potential solutions. These individuals are adjusted during an iterative process (generations) by performing three principal operations: mutation, crossover, and selection.
Initially, each individual x i G = x i , 1 G x i , 2 G x i , D G T is randomly generated, where i = 1 , 2 , 3 , , N with N representing the total number of population members, D denoting the dimension of the problem, and G indicating the current generation.
The mutation operation generates a mutant vector v i G = v i , 1 G v i , 2 G v i , D G T as follows:
v i G = x r 1 G + F x r 2 G x r 3 G ,
where x r 1 G , x r 2 G , and x r 3 G are individuals chosen randomly such that r 1 , r 2 , r 3 1 , N and i r 1 r 2 r 3 . Moreover, F 0 , 2 is called the amplification factor.
A trial vector u i G = u i , 1 G u i , 2 G u i , D G T is created by the following crossover operation:
u i , j G = v i , j G if r C R or j = r j x i , j G if r > C R and j r j ,
where C R [ 0 , 1 ] is the crossover constant, and r [ 0 , 1 ] and r j 1 , D are random numbers.
In the selection operation, the trial vector u i G is compared to the current vector x i G according to the following scheme:
x i G + 1 = u i G if f u i G < f x i G x i G otherwise ,
where f is an objective function. Trial vector u i G replaces x i G + 1 if u i G yields a better solution; otherwise, x i G is retained in the next iteration. A detailed description of DE can be found in [29].

4. Approach Description

This section presents a comprehensive description of the objective function formulation and introduces the algorithm for solving inverse kinematics using a hybrid differential evolution approach.

4.1. Objective Function Formulation

This work proposes solving the inverse kinematics (IK) problem as a global constrained optimization task. The objective function is formulated to minimize the error between the desired end-effector pose R d , t d and the current end-effector pose R q , t q , which can be computed using Equations (2) and (3).
The objective function f is defined as
f q = k t t d t q + k R R d R q ,
where t d t q represents a Euclidean norm error between the desired and the current position, and R d R q represents the Frobenius norm error between the desired and the current orientation. Additionally, k t and k R are positive weight factors.
The optimization problem is then defined as follows:
arg min q f q , subject to q l < q < q u ,
where q l and q u are the lower and upper joint boundary, respectively. The joint boundary represents the joint limits. They are defined as
q l = q l , 1 q l , 2 q l , n T , q u = q u , 1 q u , 2 q u , n T .
The constrained optimization in (12) is reformulated as an unconstrained optimization problem using quadratic penalty functions. The proposed objective function f q is then defined as follows:
f q = f q + γ j = 1 n max 0 , q l , j q j 2 + j = 1 n max 0 , q j q u , j 2 ,
where γ > 0 is a coefficient that scales the contribution of the penalty functions. By setting γ larger, constraints are penalized more severely. Moreover, when q l , j q j 0 and q j q u , j 0 , the constraint in dimension j is satisfied.
Finally, the proposed optimization problem is given as
arg min q f q .
Notice that the proposed objective function (13) incorporates the weighted error in both position and orientation, along with a penalty scheme. By minimizing the objective function, the joint configurations result in lower position and orientation errors while ensuring feasible joint solutions.

4.2. Inverse Kinematics Using Hybrid Differential Evolution

We propose enhancing the exploitation of differential evolution (DE) with Jacobian-based refinements, tracking the improvements of the best individuals over generations. If the position of the best individual stagnates, a Jacobian pseudoinverse step is performed to generate a candidate solution. This candidate solution replaces the current best individual if it provides a better solution. This operation enhances the local exploitation capabilities of DE with Jacobian-based refinements while preserving the exploration capabilities of DE.
The best individual is considered to be stagnating when there is not improvement after several generations. An l G counter tracks the number of consecutive unsuccessful modifications at generation G. If l G reaches a predefined stagnation limit L, a Jacobian-based refinement is performed. This process is called the Jacobian pseudoinverse step.
The Jacobian pseudoinverse step produces a candidate solution based on the conventional numerical method (4). The candidate solution w g G is generated as follows:
w g G = x g G + J ( x g G ) e ( x g G ) ,
where x g G denotes the best individual at generation G. The candidate solution is then compared against the current best solution according to the following scheme:
x g G + 1 = w g G if f w g G < f x g G x g G otherwise ,
which is a selection operation. If candidate solution w g G produces a better solution than x g G , w g G replaces the best individual for the next generation. Otherwise, x g G is retained.

4.3. Proposed Algorithm

The proposed inverse kinematics algorithm, based on hybrid differential evolution, is outlined in Algorithm 1. Initially, individuals are generated randomly based on the following operation:
x i , j = q l , j + r q u , j q l , j
where r [ 0 , 1 ] is a random number.
The algorithm performs the mutation, recombination, and selection operation on each individual in the population. Subsequently, the algorithm identifies the best individual x g G . It then checks whether the best individual has stagnated, determined by whether the stagnation counter l G exceeds the predefined limit L (i.e., l G > L ). If stagnation is detected, the proposed Jacobian pseudoinverse operation is performed. In this scenario, a candidate solution w g G is computed using the Jacobian pseudoinverse step. Local refinements are made if w g G proves to be a better solution than x g G . Additionally, the stagnation counter l G > L increases when f x g G + 1 < f x g G , indicating an unsuccessful improvement. This process is repeated until the stopping criteria are met. Finally the algorithm returns the individual with the best fitness as the solution.
Algorithm 1 Proposed inverse kinematics based on hybrid differential evolution.
1:
set objective function f as in (13)
2:
set F [ 0 , 2 ] and C R [ 0 , 1 ] values
3:
set joint boundary q l and q u
4:
set stagnation counter l = 0 and stagnation limit L
5:
for each individual i do
6:
      for each dimension j do
7:
            randomly compute r [ 0 , 1 ]
8:
             x i , j = q l , j + r q u , j q l , j
9:
      end
10:
end
11:
repeat
12:
      // Mutation, recombination, and selection operations on population:
13:
      for each individual i do
14:
            randomly choose r 1 , r 2 , r 3 , such that i r 1 r 2 r 3
15:
             v i G = x r 1 G + F x r 2 G x r 3 G
16:
            randomly compute r j 1 , D
17:
            for each dimension j do
18:
                  randomly compute r [ 0 , 1 ]
19:
                  if r C R  or  j = r j  then
20:
                         u i , j G = v i , j G
21:
                  otherwise
22:
                         u i , j G = x i , j G
23:
                  end
24:
            end
25:
            if  f u i G < f x i G  then
26:
                   x i G + 1 = u i G
27:
            end
28:
      end
29:
      // Jacobian pseudoinverse operation:
30:
      find best individual g
31:
      if  l G > L  then
32:
             w g G = x g G + J ( x g G ) e ( x g G )
33:
            if  f w g G < f x g G
34:
                   x g G + 1 = w g G
35:
            otherwise
36:
                   x g G + 1 = x g G
37:
            end
38:
             l G = 0
39:
      end
40:
      if  f x g G + 1 < f x g G  then
41:
             l G + 1 = 0
42:
      otherwise
43:
             l G + 1 = l G + 1
44:
      end
45:
until the stopping criteria are met
46:
Return the individual with the best fitness as the solution

5. Simulation and Experimental Results

Experiments aim to test the proposed inverse kinematics algorithm under different manipulator structures. Simulations perform a comparison among metaheuristic algorithms. Moreover, real-world experiments validate the applicability of the proposal.

5.1. Simulation Experiments

The objective of these simulations is to compare the performance of various metaheuristic algorithms—BA (BA), differential evolution (DE), particle swarm optimization (PSO), invasive weed optimization (IWO), and the imperialist competitive algorithm (ICA)—in solving the inverse kinematics for both the position and orientation of the Puma 560 robot (6 DOF), Baxter robot (7 DOF), and KUKA iiwa robot (7 DOF). Moreover, simulations are performed using Matlab R2024b.
Each simulation consists of G = 300 iterations and a population of N = 30 individuals. The following parameters were defined: k t = 1.5 , k R = 0.8 , γ = 1000 , C R = 0.9 , and F = 0.6 ; the Denavit–Hartenberg (DH) convention was used to describe the kinematic structure of the manipulators used in the simulations. Table 2 presents the DH parameters for the Puma-560 manipulator. Table 3 provides the DH parameters of the Baxter manipulator. Table 4 lists the DH parameters for the KUKA iiwa manipulator. Moreover, the illustrations in Figure 1, Figure 2 and Figure 3 show the coordinate frames’ assignment for the considered manipulators.
The joint limits for the Puma-560 robot are as follows:
q l = 160 45 225 110 100 266 T
q u = 160 225 45 170 100 266 T
The joint limits for the Baxter robot are as follows:
q l = 97.5 123 175 3 175 90 175 T
q u = 97.5 60 175 150 175 120 175 T
The joint limits for the KUKA iiwa robot are as follows:
q l = 170 120 170 120 170 120 175 T
q u = 170 120 170 120 170 120 175 T
In all cases, the equivalent values in radians are used in the algorithms.
The desired end-effector poses are defined with a set of 100 random positions and orientations generated in a valid workspace for the robotic manipulators, as shown in Figure 4. All random poses are reachable. Moreover, the proposed approach runs for every randomly desired pose independently. The best fitness value of each run is kept for statistical analysis.
Comparisons aim to analyze the statistical variation in the results of each algorithm. Boxplot graphics are used as a visual aid to identify the algorithm with the lowest variability, characterized by lower dispersion and lower fitness function values. A lower fitness value corresponds to smaller errors in both position and orientation. Moreover, lower fitness values indicate that joint values are feasible, as no penalties are applied. The results are presented using statistical measures such as mean, standard deviation, and the best and worst outcomes of each algorithm, all of which are summarized in tables.
In the following paragraphs, we consider the term ’standard algorithm’ for algorithms that have been applied as described by their author, while the term ’hybrid algorithm’ is used for algorithms that include the Jacobian pseudoinverse operations.
Figure 5 presents a comparison of data dispersion between standard and hybrid (H) algorithms using a boxplot. It is evident that the standard algorithms, Figure 5a, exhibit higher dispersion compared to the hybrid algorithms, Figure 5b. The DE and IWO hybrid algorithms demonstrate similar performance. Table 5 provides a comparison of the statistical measures obtained by the algorithms, showing that the DE hybrid algorithm (DE-H) achieves the best performance in solving the inverse kinematics of the Puma-560 robot.
Figure 6 illustrates the simulation results for the 7 DOF Baxter robot. Figure 6a shows the data dispersion of standard algorithms, while Figure 6b demonstrates that the hybrid DE algorithm achieved the best result. Table 6 compares the statistical measures obtained by the algorithms in solving the inverse kinematics of the Baxter robot. Similar to the previous case, the hybrid DE algorithm (DE-H) exhibits the best performance.
Finally, Figure 7 presents the simulation results of KUKA iiwa robot. Figure 7a displays a boxplot of the error obtained by the standard algorithms, while Figure 7b shows a boxplot of the performance of the hybrid algorithms. The distribution comparison indicates that hybrid algorithms perform better, with DE and IWO demonstrating similar performance. Table 7 reveals that DE hybrid algorithm (DE-H) achieves the most significant improvement for the KUKA iiwa Robot.

5.2. Second Simulation Experiment

In this part of the simulations, an edge-case experiment is conducted to evaluate the proposed approach. To solve the inverse kinematics, a desired end-effector position is proposed within the workspace to ensure it is reachable. However, some desired positions cannot be achieved with certain orientations. Therefore, appropriate orientation selection is crucial. This issue makes the inverse kinematics problem challenging to solve.
In these edge cases, gains k t and k R in Equation (11) can be adjusted to give priority to minimize the error between the desired and the current end-effector position, rather than orientation errors.
The edge-case experiments involve defining a reachable desired position with an unreachable desired orientation for the Baxter robot. The proposed approach is run independently 100 times for the same pose, and the best fitness value is retained for statistical analysis to compare all considered algorithms. Additionally, position and orientation errors between the desired and current end-effector poses are analyzed (see Equation (11)).
The experimental setup is conducted as follows: gains are set to k t = 1.5 and k R = 0.25 to give priority to minimize the position error. Moreover, G = 300 , N = 30 , γ = 1000 , C R = 0.9 , and F = 0.6 . Finally, the desired end-effector pose is defined as
T d = R d t d 0 1 = 0 0 1 0.5 0 1 0 0.4 1 0 0 0.6 0 0 0 1
Figure 8 presents the statistical results of the best fitness value achieved by each algorithm. As shown, DE-H outperformed the others, demonstrating a smaller data distribution and lower fitness values. It is worth noting that the best fitness values are around 0.15 due to the significant orientation error. Consequently, position and orientation errors are now compared independently for statistical analysis.
Table 8 presents the position error results. The DE-H algorithm outperformed the others, achieving the lowest mean and standard deviation (std) values. Even the worst position error obtained by DE-H is better than the mean errors of BA-H, PSO-H, and IWO-H. Although the best position error is achieved by ICA-H, its performance is considered an outlier due to the larger data distribution observed in Figure 8.
In contrast to the position errors, the orientation errors reported in Table 9 are significantly higher, as the desired orientation is considered unreachable.
As expected, DE-H reported lower mean, standard deviation (std), and worst-case orientation error values compared to those in reachable poses. Although the best orientation error was achieved by PSO-H, its data distribution, as shown in Figure 8, is considerably larger than that of DE-H.
We present another edge-case experiment involving four randomly selected unreachable desired positions, each with a corresponding reachable desired orientation, for the Baxter robot. Table 10 presents the position and orientation error results for each case, while Figure 9 illustrates the performance of the proposed approach in handling these unreachable poses. Coordinate frames in red represent the unreachable poses and coordinate frames in blue the achieved ones. Notice that all coordinate frames are adjusted with respect to orientation errors; however, position errors are not.
The results demonstrate that the proposed approach successfully solves the inverse kinematics problem by minimizing position errors, even when the desired orientation is unreachable.

5.3. Real-World Experimental Results

Real-world experiments were conducted to demonstrate the applicability of the proposed approach. The optimal joint configuration computed by this method can serve as a reference for point-to-point motion planning. For the experiments, a cubic polynomial trajectory was used to compute the joint motion from an initial joint position q i to the joint reference q r at a desired run time T.
The experimentation consists of two phases. First, the proposed approach solves the inverse kinematics for a desired end-effector pose to estimate a joint reference q r . Then, the manipulator robot follows a cubic polynomial trajectory based on the initial joint configuration q i and a run time T.
A 5 DOF KUKA YouBot was used for experimentation, as shown in Figure 10. The DH parameters are provided in Table 11 and the coordinate frame assignment is presented in Figure 11. The proposed algorithm was implemented using Matlab and the ROS environment. ROS components on the KUKA YouBot provide an internal PID controller in the joint space, which is convenient for the considered trajectory planning. A point-to-point trajectory planning is performed on an external computer with Matlab and the ROS toolbox.
The lower and upper joint limits are defined as
q l = 169 65 150 102.5 167.5 T q u = 169 90 146 102.5 167.5 T
In Experiment 1, a run time of T = 8 seconds is set, and the desired pose of the end-effector is specified as follows:
T d = R d t d 0 1 = 1 0 0 0.2 0 1 0 0.2 0 0 1 0 0 0 0 1
The inverse kinematics solution obtained through the proposed approach is
q r = 44.15 39.31 54.6 13.57 44.43 T
The initial joint configuration is selected as
q i = 0 90 0 90 0 T
The joint position and velocities for the motion planning in Experiment 1 are presented in Figure 12. Additionally, Figure 13 illustrates the final joint configuration along with the joint motion results as measured by the encoders.
For Experiment 2, a run time of T = 4 seconds is set, and the desired pose of the end-effector is defined as
T d = R d t d 0 1 = 1 0 0 0.2 0 1 0 0.2 0 0 1 0 0 0 0 1
The inverse kinematics solution for Experiment 2, obtained through the proposed approach, is
q r = 44.10 40.46 50.10 13.97 45.37 T
and the considered initial joint configuration for this test is
q i = 0 90 45 45 0 T
The joint position and velocities of the motion planning for Experiment 2 are presented in Figure 14. Additionally, Figure 15 illustrates the final joint configuration along with the joint motion results measured by the encoders.
As observed in Figure 13b and Figure 15b, the internal controller follows the given joint references given in Figure 12 and Figure 14, respectively. This indicates that the manipulator reached the optimal joint configurations computed by the proposed approach. Furthermore, Figure 13 and Figure 15 illustrate the real-world applicability of the proposed approach; the computed joint configurations are physically reachable.
For Experiment 3, a runtime of T = 4 s is set. In this case, a desired end-effector pose is defined with a reachable position but an unreachable orientation. The desired pose is specified as follows:
T d = R d t d 0 1 = 0 0 1 0.2 0 1 0 0.3 1 0 0 0.4 0 0 0 1
The inverse kinematics solution for experiment 3 is
q r = 56.31 83.19 35.95 42.76 0.0028 T
The initial joint configuration considered for the polynomial trajectory is as follows:
q i = 0 90 0 90 0 T
The joint positions and velocities for the motion planning are shown in Figure 16. Additionally, Figure 17 presents the final joint configuration along with the joint motion results measured by the encoders.
The achieved end-effector pose is
T n 0 = 0 0.832 0.554 0.2 0 0.554 0.832 0.3 1 0 0 0.4 0 0 0 1
As can be seen, the desired position is reached. The desired and current positions are practically the same. However, the desired and current orientations are only approximately aligned. As expected, the proposed approach prioritizes minimizing position errors over orientation errors, given that the desired orientation is not reachable. It is worth noting that the implementation in real-world experiments further demonstrates that the inverse kinematics solutions are physically feasible.
The proposed algorithm was executed on a computer with an Intel i7 processor and 16 GB of RAM. The inverse kinematics estimation took less than one second for each tested point. If further speed is required, the performance of metaheuristic algorithms can be enhanced using parallel architectures and dedicated hardware, such as NVIDIA CUDA.

6. Discussion

The proposed approach was applied in three simulation experiments involving the Puma-560, Baxter, and KUKA iiwa robots. The inverse kinematics were successfully solved in each case, demonstrating the applicability of the system across different configurations. Among the tested algorithms, differential evolution (DE) consistently outperformed BA, PSO, and ICA. While the performance of DE and IWO exhibited similar performance across experiments, DE reported the lowest dispersion of the data.
When comparing the experimental results with and without hybridization, a significant improvement in the solution of the inverse kinematics is evident across all algorithms. The Jacobian step enhances the exploitation capabilities of the algorithm; algorithms like PSO, ICA, and BA exhibit stagnation, which indicates weak exploration capabilities, whereas DE and IWA demonstrate a strong exploration performance.
DE-H reported better fitness value results in all tests, achieving the lowest mean and standard deviation (std) values. This indicates that DE-H achieved the smallest error in both position and orientation with precision, along with the smallest data distribution, reflecting more consistent results. In contrast, ICA and PSO performed poorly in all tests, achieving the worst results in terms of mean and std values. Additionally, the performance of IWO-H was very similar to DE-H. However, DE-H outperformed all the other algorithms by achieving lower mean and std values.
The evaluation of the standard deviation ( 5.8348   ×   10 3 ) indicates that the method achieves sufficient precision in both position and orientation, making it suitable for applications such as medical procedures, where fine adjustments are critical.
The proposed approach was also applied in real-world experimentation, where the KUKA YouBot robot was considered as a case study. The application on the real robot demonstrates that the inverse kinematics results are acceptable, confirming that the constrained problem is solved despite the DE algorithm not being specifically designed for constrained problems.
A drawback of the conventional Jacobian pseudoinverse is that the inversion of J cannot always be guaranteed. Singular configurations cause J to become rank deficient, leading to system instability. In this work, a Jacobian pseudoinverse step is used to generate a candidate solution. In the presence of singularities, unfeasible solutions are avoided in the Jacobian pseudoinverse operation, as only improved joint solutions replace the current ones. This mechanism effectively prevents singularities.
Future work will focus on solving inverse kinematics for a mobile manipulator [16], incorporating the Jacobian step for fine-tuning. Additionally, we aim to extend the use of inverse kinematics to trajectory tracking and address grasping problems on platforms equipped with dual manipulators [35,36].

7. Conclusions

The hybrid metaheuristic algorithm approach proposed in this paper has demonstrated its applicability across different robotic manipulators by successfully solving inverse kinematics in two simulated experiments with six and seven degrees of freedom, as well as in an experiment with a real robot with five degrees of freedom.
Among the algorithms tested in this research, DE and IWO exhibited similar performance across the experiments. However, DE achieved the lowest scatter in the data, effectively solving both position and orientation with constraints, even though the algorithm was not designed to work with constraints.
The inclusion of the Jacobian matrix steps shows a significant improvement in the exploitation capabilities of the algorithms, However, algorithms with inherently poor exploration characteristics showed only marginal improvement.
Future work applying the methods proposed in this study promises favorable results for more complex problems, such as dual-arm systems and mobile manipulators. This work considers solving the inverse kinematics for manipulators with open kinematic chains. However, it is appealing to extend this work to solve the inverse kinematics of closed kinematics such as parallel manipulators.

Author Contributions

Conceptualization, C.L.-F.; methodology, C.L.-F., J.H.-B. and J.P.-L.; software, J.P.-L. and M.L.-F.; validation, J.P.-L. and M.L.-F.; formal analysis, C.L.-F. and N.A.-D.; investigation, C.L.-F., J.H.-B. and J.P.-L.; resources, J.H.-B. and M.L.-F.; writing, J.P-L; writing—review and editing, C.L.-F. and J.H.-B.; visualization, N.A.-D. and M.L.-F.; supervision, C.L.-F. and J.H.-B.; project administration, C.L.-F. and N.A.-D.; funding acquisition, C.L.-F. and N.A.-D. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Data Availability Statement

Data can be made available upon request to interested researchers.

Acknowledgments

We thank the University of Guadalajara for supporting this work.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Papadopoulos, E.; Aghili, F.; Ma, O.; Lampariello, R. Robotic manipulation and capture in space: A survey. Front. Robot. AI 2021, 8, 686723. [Google Scholar] [CrossRef] [PubMed]
  2. Garriz, C.; Domingo, R. Development of trajectories through the kalman algorithm and application to an industrial robot in the automotive industry. IEEE Access 2019, 7, 23570–23578. [Google Scholar] [CrossRef]
  3. Nisar, S.; Hameed, A.; Kamal, N.; Hasan, O.; Matsuno, F. Design and realization of a robotic manipulator for minimally invasive surgery with replaceable surgical tools. IEEE/ASME Trans. Mechatronics 2020, 25, 2754–2764. [Google Scholar] [CrossRef]
  4. Siciliano, B.; Sciavicco, L.; Villani, L.; Oriolo, G. Robotics: Modelling, Planning and Control; Springer: London, UK, 2009. [Google Scholar]
  5. Park, T. Numerical Methods for Mixed Differential-Algebraic Equations in Kinematics and Dybamics (Constraints, Singularity, Nonholonomic, Holonomic, Condition Number); The University of Iowa: Iowa City, IA, USA, 1985. [Google Scholar]
  6. Kucuk, S.; Bingul, Z. Inverse kinematics solutions for industrial robot manipulators with offset wrists. Appl. Math. Model. 2014, 38, 1983–1999. [Google Scholar] [CrossRef]
  7. Bayro-Corrochano, E.; Zamora-Esquivel, J. Differential and inverse kinematics of robot devices using conformal geometric algebra. Robotica 2007, 25, 43–61. [Google Scholar] [CrossRef]
  8. Almusawi, A.R.; Dülger, L.C.; Kapucu, S. A new artificial neural network approach in solving inverse kinematics of robotic arm (denso vp6242). Comput. Intell. Neurosci. 2016, 2016, 5720163. [Google Scholar] [CrossRef] [PubMed]
  9. Aggarwal, L.; Aggarwal, K.; Urbanic, R.J. Use of artificial neural networks for the development of an inverse kinematic solution and visual identification of singularity zone (s). Procedia Cirp 2014, 17, 812–817. [Google Scholar] [CrossRef]
  10. Lu, J.; Zou, T.; Jiang, X. A neural network based approach to inverse kinematics problem for general six-axis robots. Sensors 2022, 22, 8909. [Google Scholar] [CrossRef]
  11. Hussain, K.; Mohd Salleh, M.N.; Cheng, S.; Shi, Y. Metaheuristic research: A comprehensive survey. Artif. Intell. Rev. 2019, 52, 2191–2233. [Google Scholar] [CrossRef]
  12. Nematzadeh, S.; Kiani, F.; Torkamanian-Afshar, M.; Aydin, N. Tuning hyperparameters of machine learning algorithms and deep neural networks using metaheuristics: A bioinformatics study on biomedical and biological cases. Comput. Biol. Chem. 2022, 97, 107619. [Google Scholar] [CrossRef]
  13. Lopez-Franco, C.; Diaz, D.; Hernandez-Barragan, J.; Arana-Daniel, N.; Lopez-Franco, M. A metaheuristic optimization approach for trajectory tracking of robot manipulators. Mathematics 2022, 10, 1051. [Google Scholar] [CrossRef]
  14. Martinez-Soltero, E.G.; Hernandez-Barragan, J. Robot navigation based on differential evolution. IFAC-PapersOnLine 2018, 51, 350–354. [Google Scholar] [CrossRef]
  15. Reyes, S.V.; Gardini, S.P. Inverse kinematics of manipulator robot using a PSO metaheuristic with adaptively exploration. In Proceedings of the 2019 IEEE XXVI International Conference on Electronics, Electrical Engineering and Computing (INTERCON), Lima, Peru, 12–14 August 2019; IEEE: Piscataway, NJ, USA, 2019; pp. 1–4. [Google Scholar]
  16. López-Franco, C.; Hernández-Barragán, J.; Alanis, A.Y.; Arana-Daniel, N.; López-Franco, M. Inverse kinematics of mobile manipulators based on differential evolution. Int. J. Adv. Robot. Syst. 2018, 15, 1729881417752738. [Google Scholar] [CrossRef]
  17. Yiyang, L.; Xi, J.; Hongfei, B.; Zhining, W.; Liangliang, S. A general robot inverse kinematics solution method based on improved PSO algorithm. IEEE Access 2021, 9, 32341–32350. [Google Scholar] [CrossRef]
  18. Linh, T.; Nguyen, T.; Nguyen, T.; Hasegawa, H.; Watanabe, D. DE-based algorithm for solving the inverse kinematics on a robotic arm manipulators. J. Phys. Conf. Ser. 2021, 1922, 012008. [Google Scholar]
  19. Gonzalez, C.; Blanco, D.; Moreno, L. Optimum robot manipulator path generation using Differential Evolution. In Proceedings of the 2009 IEEE Congress on Evolutionary Computation, Trondheim, Norway, 18–21 May 2009; IEEE: Piscataway, NJ, USA, 2009; pp. 3322–3329. [Google Scholar]
  20. Almaghout, K.; Rezaee, A. PSO Based Solution for 6-DOF Serial Manipulator Inverse Kinematics Problem. Int. J. Robot. Theory Appl. 2023, 9, 20–25. [Google Scholar]
  21. Dereli, S.; Köker, R. Simulation based calculation of the inverse kinematics solution of 7-DOF robot manipulator using artificial bee colony algorithm. SN Appl. Sci. 2020, 2, 27. [Google Scholar] [CrossRef]
  22. Masajedi, P.; Heidari Shirazi, K.; Ghanbarzadeh, A. Verification of bee algorithm based path planning for a 6DOF manipulator using ADAMS. J. Vibroeng. 2013, 15, 805–815. [Google Scholar]
  23. Huang, H.C.; Chen, C.P.; Wang, P.R. Particle swarm optimization for solving the inverse kinematics of 7-DOF robotic manipulators. In Proceedings of the 2012 IEEE International Conference on Systems, Man, and Cybernetics (SMC), Seoul, Republic of Korea, 14–17 October 2012; IEEE: Piscataway, NJ, USA, 2012; pp. 3105–3110. [Google Scholar]
  24. Hernandez-Barragan, J.; Lopez-Franco, C.; Antonio-Gopar, C.; Alanis, A.Y.; Arana-Daniel, N. The inverse kinematics solutions for robot manipulators based on firefly algorithm. In Proceedings of the 2018 IEEE Latin American Conference on Computational Intelligence (LA-CCI), Gudalajara, Mexico, 7–9 November 2018; IEEE: Piscataway, NJ, USA, 2018; pp. 1–5. [Google Scholar]
  25. Rokbani, N.; Mirjalili, S.; Slim, M.; Alimi, A.M. A beta salp swarm algorithm meta-heuristic for inverse kinematics and optimization. Appl. Intell. 2022, 52, 10493–10518. [Google Scholar] [CrossRef]
  26. López-Muñoz, R.; Portilla-Flores, E.A.; Corona-Ramírez, L.G.; Vega-Alvarado, E.; Maya-Rodríguez, M.C. Inverse kinematics: An alternative solution approach applying metaheuristics. Appl. Sci. 2023, 13, 6543. [Google Scholar] [CrossRef]
  27. Nyong-Bassey, B.E.; Epemu, A.M. Inverse kinematics analysis of novel 6-DOF robotic arm manipulator for oil and gas welding using meta-heuristic algorithms. Int. J. Robot. Autom. Sci. 2022, 4, 13–22. [Google Scholar]
  28. Wu, H.; Zhang, X.; Song, L.; Zhang, Y.; Gu, L.; Zhao, X. Wild Geese Migration Optimization Algorithm: A New Meta-Heuristic Algorithm for Solving Inverse Kinematics of Robot. Comput. Intell. Neurosci. 2022, 2022, 5191758. [Google Scholar] [CrossRef] [PubMed]
  29. Storn, R.; Price, K. Differential evolution—A simple and efficient heuristic for global optimization over continuous spaces. J. Glob. Optim. 1997, 11, 341–359. [Google Scholar] [CrossRef]
  30. Kennedy, J.; Eberhart, R. Particle swarm optimization. In Proceedings of the ICNN’95-International Conference on Neural Networks, Perth, Australia, 7 November–1 December 1995; IEEE: Piscataway, NJ, USA, 1995; Volume 4, pp. 1942–1948. [Google Scholar]
  31. Pham, D.T.; Ghanbarzadeh, A.; Koç, E.; Otri, S.; Rahim, S.; Zaidi, M. The bees algorithm—A novel tool for complex optimisation problems. In Intelligent Production Machines and Systems; Elsevier: Amsterdam, The Netherlands, 2006; pp. 454–459. [Google Scholar]
  32. Mehrabian, A.R.; Lucas, C. A novel numerical optimization algorithm inspired from weed colonization. Ecol. Inform. 2006, 1, 355–366. [Google Scholar] [CrossRef]
  33. Atashpaz-Gargari, E.; Lucas, C. Imperialist competitive algorithm: An algorithm for optimization inspired by imperialistic competition. In Proceedings of the 2007 IEEE Congress on Evolutionary Computation, Singapore, 25–28 September 2007; IEEE: Piscataway, NJ, USA, 2007; pp. 4661–4667. [Google Scholar]
  34. Spong, M.; Hutchinson, S.; Vidyasagar, M. Robot Dynamics and Control; Wiley: Hoboken, NJ, USA, 2004. [Google Scholar]
  35. Hernandez-Barragan, J.; Martinez-Soltero, G.; Rios, J.D.; Lopez-Franco, C.; Alanis, A.Y. A metaheuristic Optimization approach to solve inverse kinematics of mobile Dual-Arm robots. Mathematics 2022, 10, 4135. [Google Scholar] [CrossRef]
  36. Wang, J.; Liu, S.; Zhang, B.; Yu, C. Inverse kinematics-based motion planning for dual-arm robot with orientation constraints. Int. J. Adv. Robot. Syst. 2019, 16, 1729881419836858. [Google Scholar] [CrossRef]
Figure 1. Coordinate frames’ assignment for the Puma-560 manipulator.
Figure 1. Coordinate frames’ assignment for the Puma-560 manipulator.
Algorithms 17 00454 g001
Figure 2. Coordinate frames’ assignment for the Baxter manipulator.
Figure 2. Coordinate frames’ assignment for the Baxter manipulator.
Algorithms 17 00454 g002
Figure 3. Coordinate frames’ assignment for the KUKA iiwa manipulator.
Figure 3. Coordinate frames’ assignment for the KUKA iiwa manipulator.
Algorithms 17 00454 g003
Figure 4. Randomly generated set of values.
Figure 4. Randomly generated set of values.
Algorithms 17 00454 g004
Figure 5. Comparison of standard and hybrid algorithms in solving inverse kinematics of the Puma-560 robot. (a) Standard algorithms. (b) Hybrid algorithms.
Figure 5. Comparison of standard and hybrid algorithms in solving inverse kinematics of the Puma-560 robot. (a) Standard algorithms. (b) Hybrid algorithms.
Algorithms 17 00454 g005
Figure 6. Comparison of standard and hybrid algorithms in solving inverse kinematics of the Baxter robot. (a) Standard algorithms. (b) Hybrid algorithms.
Figure 6. Comparison of standard and hybrid algorithms in solving inverse kinematics of the Baxter robot. (a) Standard algorithms. (b) Hybrid algorithms.
Algorithms 17 00454 g006
Figure 7. Comparison of standard and hybrid algorithms in solving inverse kinematics of the KUKA iiwa robot. (a) Standard algorithms. (b) Hybrid algorithms.
Figure 7. Comparison of standard and hybrid algorithms in solving inverse kinematics of the KUKA iiwa robot. (a) Standard algorithms. (b) Hybrid algorithms.
Algorithms 17 00454 g007
Figure 8. Comparison of hybrid algorithms for solving the inverse kinematics of the Baxter robot in an orientation-unreachable end-effector pose.
Figure 8. Comparison of hybrid algorithms for solving the inverse kinematics of the Baxter robot in an orientation-unreachable end-effector pose.
Algorithms 17 00454 g008
Figure 9. Unreachable pose experiment results. Coordinate frames in red represents the unreachable poses and coordinate frames in blue the achieved ones.
Figure 9. Unreachable pose experiment results. Coordinate frames in red represents the unreachable poses and coordinate frames in blue the achieved ones.
Algorithms 17 00454 g009
Figure 10. KUKA YouBot manipulator with 5 DOF.
Figure 10. KUKA YouBot manipulator with 5 DOF.
Algorithms 17 00454 g010
Figure 11. Coordinate frames’ assignment for the KUKA YouBot manipulator.
Figure 11. Coordinate frames’ assignment for the KUKA YouBot manipulator.
Algorithms 17 00454 g011
Figure 12. Time history with a cubic polynomial timing law for Experiment 1. (a) Joint positions. (b) Joint velocities.
Figure 12. Time history with a cubic polynomial timing law for Experiment 1. (a) Joint positions. (b) Joint velocities.
Algorithms 17 00454 g012
Figure 13. KUKA YouBot final joint configuration for Experiment 1. (a) Real-world final joint configuration. (b) Joint motion results measured by encoders.
Figure 13. KUKA YouBot final joint configuration for Experiment 1. (a) Real-world final joint configuration. (b) Joint motion results measured by encoders.
Algorithms 17 00454 g013
Figure 14. Time history with a cubic polynomial timing law for Experiment 2. (a) Joint positions. (b) Joint velocities.
Figure 14. Time history with a cubic polynomial timing law for Experiment 2. (a) Joint positions. (b) Joint velocities.
Algorithms 17 00454 g014
Figure 15. KUKA YouBot final joint configuration for Experiment 2. (a) Real-world final joint configuration. (b) Joint motion results measured by encoders.
Figure 15. KUKA YouBot final joint configuration for Experiment 2. (a) Real-world final joint configuration. (b) Joint motion results measured by encoders.
Algorithms 17 00454 g015
Figure 16. Time history with a cubic polynomial timing law for Experiment 3. (a) Joint positions. (b) Joint velocities.
Figure 16. Time history with a cubic polynomial timing law for Experiment 3. (a) Joint positions. (b) Joint velocities.
Algorithms 17 00454 g016
Figure 17. KUKA YouBot final joint configuration for Experiment 3. (a) Real-world final joint configuration. (b) Joint motion results measured by encoders.
Figure 17. KUKA YouBot final joint configuration for Experiment 3. (a) Real-world final joint configuration. (b) Joint motion results measured by encoders.
Algorithms 17 00454 g017
Table 1. State of the art related work.
Table 1. State of the art related work.
ReferenceAlgorithmDOFsOrientationBoundariesRobot Application
[15]PSO5,6-DOF
[16]DE6,7,8,9-DOF
[17]PSO, multi-PSP, imp PSO6-DOF
[18]DE5-DOF
[19]DE6-DOF
[20]PSO6-DOF
[21]ABC6-DOF
[22]BA6-DOF
[23]PSO7-DOF
[24]FA5-DOF
[25] β - S S A 6,8-DOF
[26]Modified DE10-DOF
[27]GWO6-DOF
[28]GMO6-DOF
Proposed MethodDE-H5,6,7-DOF
Table 2. Puma-560 manipulator DH parameters.
Table 2. Puma-560 manipulator DH parameters.
Jointa [m] α [rad]d [m] Θ [rad]
10 π / 2 0 q 1
20.431800 q 2
30.0203 π / 2 0.15 q 3
40 π / 2 0.4318 q 4
50 π / 2 0 q 5
6000 q 6
Table 3. Baxter manipulator DH parameters.
Table 3. Baxter manipulator DH parameters.
Jointa [m] α [rad]d [m] Θ [rad]
10.069 π / 2 0.270 q 1
20 π / 2 0 q 2
30.069 π / 2 0.364 q 3
40 π / 2 0 q 4
50.01 π / 2 0.374 q 5
60 π / 2 0 q 6
7000.28 q 7
Table 4. KUKA iiwa manipulator DH parameters.
Table 4. KUKA iiwa manipulator DH parameters.
Jointa [m] α [rad]d [m] Θ [rad]
10 π / 2 0.360 q 1
20 π / 2 0 q 2
30 π / 2 0.420 q 3
40 π / 2 0 q 4
50 π / 2 0.400 q 5
60 π / 2 0 q 6
7000.126 q 7
Table 5. Comparison of the statistical performance of standard and hybrid algorithms in solving the inverse kinematics of the Puma-560 robot. Bold text indicates better fitness values.
Table 5. Comparison of the statistical performance of standard and hybrid algorithms in solving the inverse kinematics of the Puma-560 robot. Bold text indicates better fitness values.
BABA-HDEDE-HPSOPSO-HICAICA-HIWOIWO-H
mean0.055880.064060.309285.8349   ×   10 4 0.599010.104830.216490.210250.031250.02216
std0.063360.082270.232735.8348   ×   10 3 0.130280.241290.19530.198450.062980.05877
best5.55 ×   10 8 4.1748 ×   10 9 1.958 ×   10 6 8.7469   ×   10 17 0.268398.9099 ×   10 17 0.006370.008055.658 ×   10 4 1.0444 ×   10 16
worst0.279540.39820.73870.058350.899760.903870.802640.917740.357210.39258
Table 6. Comparison of the statistical performance of standard and hybrid algorithms in solving the inverse kinematics of the Baxter robot. Bold text indicates better fitness values.
Table 6. Comparison of the statistical performance of standard and hybrid algorithms in solving the inverse kinematics of the Baxter robot. Bold text indicates better fitness values.
BABA-HDEDE-HPSOPSO-HICAICA-HIWOIWO-H
mean0.108140.089950.377022.2135   ×   10 3 0.507890.082820.290660.282970.010560.01515
std0.073060.093740.190668.3733   ×   10 3 0.091580.168580.179080.184310.028450.04382
best6.277 ×   10 5 2.023 ×   10 16 0.001462.0507 ×   10 15 0.288681.182 ×   10 16 0.009250.012810.000521.034   ×   10 16
worst0.322820.347450.716760.050460.712120.684620.887350.76190.213140.31733
Table 7. Comparison of the statistical performance of standard and hybrid algorithms in solving the inverse kinematics of the KUKA iiwa robot. Bold text indicates better fitness values.
Table 7. Comparison of the statistical performance of standard and hybrid algorithms in solving the inverse kinematics of the KUKA iiwa robot. Bold text indicates better fitness values.
BABA-HDEDE-HPSOPSO-HICAICA-HIWOIWO-H
mean0.0707880.038390.541761.713   ×   10 3 0.584310.098820.249720.218843.777 ×   10 3 3.104 ×   10 3
std0.060560.056180.149319.085   ×   10 3 0.100270.213860.170550.157580.011210.01208
best2.514 ×   10 7 2.635 ×   10 16 0.001041.024 ×   10 16 0.285847.124   ×   10 17 0.006950.003430.000581.517 ×   10 16
worst0.268050.238920.819660.067880.795640.806860.698710.795230.068010.06838
Table 8. Statistical comparison of the performance of hybrid algorithms in solving the inverse kinematics of the Baxter robot with an unreachable desired end-effector orientation. Bold text indicates superior position error values.
Table 8. Statistical comparison of the performance of hybrid algorithms in solving the inverse kinematics of the Baxter robot with an unreachable desired end-effector orientation. Bold text indicates superior position error values.
BA-HDE-HPSO-HICA-HIWO-H
mean0.001253.848   ×   10 4 0.090773.921 ×   10 3 0.011339
std0.007610.001250.044600.001440.00541
best3.809 ×   10 11 3.706 ×   10 6 0.012056.844   ×   10 16 0.00190
worst0.073739.217   ×   10 3 0.210370.010130.02502
Table 9. Statistical comparison of the performance of hybrid algorithms in solving the inverse kinematics of the Baxter robot with an unreachable desired end-effector orientation. Bold text indicates lower orientation error values.
Table 9. Statistical comparison of the performance of hybrid algorithms in solving the inverse kinematics of the Baxter robot with an unreachable desired end-effector orientation. Bold text indicates lower orientation error values.
BA-HDE-HPSO-HICA-HIWO-H
mean0.805840.627860.998341.20060.64396
std0.17020.058010.328690.356450.11902
best0.611190.590240.371520.620330.54221
worst1.25911.03531.82441.92671.1768
Table 10. Position and orientation error results of unreachable poses in Baxter robot.
Table 10. Position and orientation error results of unreachable poses in Baxter robot.
Random PosePosition ErrorOrientation Error
10.479793.1913 ×   10 5
20.732549.575 ×   10 5
30.711563.0564 ×   10 4
40.949693.2291 ×   10 5
Table 11. DH parameters of KUKA YouBot manipulator.
Table 11. DH parameters of KUKA YouBot manipulator.
Jointa [m] α [rad]d [m] Θ [rad]
10.033 π / 2 0.147 q 1
20.15500 q 2
30.13500 q 3
40 π / 2 0 q 4
5000.2174 q 5
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.

Share and Cite

MDPI and ACS Style

Hernandez-Barragan, J.; Plascencia-Lopez, J.; Lopez-Franco, M.; Arana-Daniel, N.; Lopez-Franco, C. Inverse Kinematics of Robotic Manipulators Based on Hybrid Differential Evolution and Jacobian Pseudoinverse Approach. Algorithms 2024, 17, 454. https://doi.org/10.3390/a17100454

AMA Style

Hernandez-Barragan J, Plascencia-Lopez J, Lopez-Franco M, Arana-Daniel N, Lopez-Franco C. Inverse Kinematics of Robotic Manipulators Based on Hybrid Differential Evolution and Jacobian Pseudoinverse Approach. Algorithms. 2024; 17(10):454. https://doi.org/10.3390/a17100454

Chicago/Turabian Style

Hernandez-Barragan, Jesus, Josue Plascencia-Lopez, Michel Lopez-Franco, Nancy Arana-Daniel, and Carlos Lopez-Franco. 2024. "Inverse Kinematics of Robotic Manipulators Based on Hybrid Differential Evolution and Jacobian Pseudoinverse Approach" Algorithms 17, no. 10: 454. https://doi.org/10.3390/a17100454

APA Style

Hernandez-Barragan, J., Plascencia-Lopez, J., Lopez-Franco, M., Arana-Daniel, N., & Lopez-Franco, C. (2024). Inverse Kinematics of Robotic Manipulators Based on Hybrid Differential Evolution and Jacobian Pseudoinverse Approach. Algorithms, 17(10), 454. https://doi.org/10.3390/a17100454

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop