Next Article in Journal
HSICCR: A Lightweight Scoring Criterion Based on Measuring the Degree of Causality for the Detection of SNP Interactions
Previous Article in Journal
Exploration of Multiple Transfer Phenomena within Viscous Fluid Flows over a Curved Stretching Sheet in the Co-Existence of Gyrotactic Micro-Organisms and Tiny Particles
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Metaheuristic Optimization Approach to Solve Inverse Kinematics of Mobile Dual-Arm Robots

by
Jesus Hernandez-Barragan
1,
Gabriel Martinez-Soltero
2,
Jorge D. Rios
1,
Carlos Lopez-Franco
2 and
Alma Y. Alanis
1,*
1
Departamento de Innovación Basada en la Información y el Conocimiento, Centro Universitario de Ciencias Exactas e Ingenierías, Universidad de Guadalajara, Guadalajara 44430, Mexico
2
Departamento de Ciencias Computacionales, Centro Universitario de Ciencias Exactas e Ingenierías, Universidad de Guadalajara, Guadalajara 44430, Mexico
*
Author to whom correspondence should be addressed.
Mathematics 2022, 10(21), 4135; https://doi.org/10.3390/math10214135
Submission received: 10 October 2022 / Revised: 2 November 2022 / Accepted: 3 November 2022 / Published: 5 November 2022
(This article belongs to the Topic Applied Metaheuristic Computing: 2nd Volume)

Abstract

:
This work presents an approach to solving the inverse kinematics of mobile dual-arm robots based on metaheuristic optimization algorithms. First, a kinematic analysis of a mobile dual-arm robot is presented. Second, an objective function is formulated based on the forward kinematics equations. The kinematic analysis does not require using any Jacobian matrix nor its estimation; for this reason, the proposed approach does not suffer from singularities, which is a common problem with conventional inverse kinematics algorithms. Moreover, the proposed method solves cooperative manipulation tasks, especially in the case of coordinated manipulation. Simulation and real-world experiments were performed to verify the proposal’s effectiveness under coordinated inverse kinematics and trajectory tracking tasks. The experimental setup considered a mobile dual-arm system based on the KUKA® Youbot® robot. The solution of the inverse kinematics showed precise and accurate results. Although the proposed approach focuses on coordinated manipulation, it can be implemented to solve non-coordinated tasks.

1. Introduction

The inverse kinematics of robot manipulators is an essential task to solve problems such as trajectory tracking, visual control, grasping, etc. Although robotic manipulators have many qualities, they have the drawback that they are fixed to a specific location with a limited workspace. To increase the manipulator’s workspace, the robot is attached to a mobile platform. These robots are called mobile manipulators and are used to solve robot manipulation tasks and mobile navigation simultaneously. However, the total degrees of freedom (DOFs) of both the manipulator and the platform give, as a result, a redundant robot [1]. The inverse kinematics for redundant robots is challenging to solve because redundancy admits several joint configurations to reach the same end-effector pose.
On the other hand, these robots allow us to solve complex tasks where just one manipulator is not enough, such as human-like tasks in domestic and industrial environments. It is important to remark that cooperative manipulation is a crucial task to solve for multiple manipulators that work together. Dual-arm systems are commonly used to deal with cooperative manipulation.
In general, there are non-coordinated manipulation and coordinated manipulation [2]. In non-coordinated manipulation, the robots perform different tasks, and the inverse kinematics can be solved independently. Robots interact with each other in coordinated manipulation, and the kinematics must be analyzed carefully to perform a task. Dual-arm systems increase the manipulation capabilities with greater accessibility. However, these systems are still fixed to a specific localization with a limited workspace. The dual-arm system is attached to a mobile platform to handle this inconvenience. The cooperative manipulation of mobile dual-arm systems is more challenging because the two manipulators interact on the same mobile platform. This inconvenience complicates the inverse kinematics, even in the case of non-coordinated manipulation.
Additionally, mobile dual-arm systems are often redundant. In this work, we introduce an approach to solve the inverse kinematics of mobile dual-arm robots. This approach deals with cooperative manipulation, especially in the case of coordinated manipulation. However, the proposed approach can also be applied to solve non-coordinated manipulation tasks. Some classical methods to compute the inverse kinematics of robot manipulators are closed-form methods and numerical approaches [3,4]. There is no guarantee of finding a closed-form solution with algebraic methods. Closed-form solutions with geometric approaches are given for simple kinematic structures. If a closed-form solution is not available, numerical approaches are often used. Most of the numerical methods are based on differential kinematics [5]. In this case, the inconvenience is given by kinematic singularities. A singularity occurs in a manipulator configuration in which a Jacobian matrix is rank-deficient. It is crucial to avoid singularities since they reduce the manipulator’s mobility, infinite solutions may exist, and inadmissible speeds may be computed.
Moreover, task priority inverse kinematics algorithms are used to solve cooperative tasks in dual-arm systems [6,7]. These methods are based on the relative Jacobian matrix, which considers the dual-arm system as a unique redundant manipulator. Then, differential kinematics can be used to solve the inverse kinematics. The disadvantage of these approaches is the task conflicts given by singularities. Due to all the drawbacks mentioned above, we propose using metaheuristics algorithms to solve the inverse kinematics of mobile dual-arm systems in this work.
The use of metaheuristic algorithms to solve inverse kinematics problems has become more common in recent years. Many versions of particle swarm optimization (PSO) have been applied to solve inverse kinematics for robotics manipulators [8,9], multi-DOF manipulators [10], and dual-arm space robots [11]. Moreover, many variants of differential evolution (DE) also have been implemented to solve the inverse kinematics of robotic manipulators [12,13] and human-like structures [14]. Artificial bee colony (ABC) and grey wolf optimization (GWO) have been also used to solve the inverse kinematics of the 4-DOF SCARA manipulator [15]. Table 1 summarizes some state-of-the-art algorithms. As can be seen, most of the authors deal with redundant robots. Moreover, most of the applications are inverse kinematic solutions for robot manipulators. The metaheuristic algorithms are: ABC, quantum PSO (QPSO), improved PSO (IMPSO), improved self-adaptive DE (ISADE), chaotic and parallelized ABC (CPABC), evolutionary algorithms (EAs), parallel learning PSO (PLPSO), genetic algorithms (GAs), and cuckoo search (CS).
In previous works, we used the covariance matrix adaptation evolution strategy (CMA-ES) algorithm to solve the inverse kinematics of robotics arms [27]. The CMA-ES algorithm stands out over other algorithms such as the bat algorithm (BA), differential search (DS), GA, and PSO. In [28], we introduced the use of DE to solve the inverse kinematics of mobile manipulators. In this case, DE outperforms other metaheuristics such as CS, hybrid biogeography-based optimization (HBBO), and teaching–learning-based optimization (TLBO). Moreover, in [29], we used the DE algorithm to solve cooperative manipulation for dual-arm systems. Based on the reported results, DE performed better than other schemes, such as a hybrid strategy based on DE and PSO (DEMPSO), the imperialist competitive algorithm (ICA), and improved TLBO (ITLBO). Furthermore, we solved the inverse kinematics problem for cooperative mobile manipulators based on self-adaptive DE (SDE) [30]. In this case, SDE achieved better results than DE, constriction factor PSO (CFPSO), the flower pollination algorithm (FPA), and a variant of ABC called KABC. Recently, we introduced the use of metaheuristics for the trajectory tracking of robot manipulators [31]. The DE algorithm outperformed the whale optimization algorithm (WOA), sine cosine algorithm (SCA), PSO, and HBBO.
The contributions of this paper are given below:
  • An approach to solve the inverse kinematics of mobile dual-arm robots is proposed for cooperative manipulation problems.
  • A kinematic model for a mobile dual-arm robot based on the KUKA® (KUKA is a registered trademark of KUKA Aktiengesellschaft Germany) Youbot® (Youbot is a registered trademark of KUKA Aktiengesellschaft Germany) system is described.
  • An objective function is formulated based on the forward kinematics equations to deal with coordinated manipulation.
  • The proposed approach avoids singularity configurations since it does not require using any Jacobian matrix.
  • A comparative study is included to compare the performance of the DE, CPABC, SDE, CS, QPSO, IMPSO, and CMA-ES algorithms.
This article is organized as follows: The next section describes the kinematic model of mobile dual-arm robots, especially for the KUKA® Youbot® system. The proposed approach is described in Section 3, where the objective function formulation and the inverse kinematics algorithm for cooperative manipulation tasks are presented. In Section 4, the experimental results for coordinated inverse kinematics and coordinated trajectory tracking tasks are given. A brief analysis of the obtained results and the future research directions are given in Section 5. Finally, conclusions are presented in Section 6.

2. Kinematic Analysis of Mobile Dual-Arm Robots

A mobile dual-arm system is composed of two manipulators attached to a mobile platform; see Figure 1. The two arms have similar kinematic structures, although they may be different. On the other hand, the mobile platform can represent a differential-drive robot, a car-like robot, or an omnidirectional robot. The advantage of using an omnidirectional robot over the other platforms is the movement capabilities that allow simultaneous displacements in any direction to reach any position and orientation in its operational space. In contrast, the differential-drive and car-like robots have limited movements due to their nonholonomic constraints [32].
In this work, we provide a kinematic model based on the KUKA® Youbot® robot [33]. This system is conformed by two identical manipulators of five DOFs composed of revolute joints and an omnidirectional mobile platform with three DOFs. Each manipulator is composed of revolute joints, and there is a gripper in the end-effector. The technical specification was carefully revised, and the kinematic analysis is given below.
The kinematic chain of the considered mobile dual-arm system is described in Figure 2. Coordinate homogeneity is considered to establish the kinematic model. Then, the following frames are defined: w represents the world frame; p is a frame attached to the mobile platform; b i is a frame attached to the beginning of the kinematic chain of the manipulator i; e i is a frame attached to the end-effector, with i = 1 , 2 . Moreover, the pose of the mobile platform is represented by q 0 , and the homogeneous matrix w T p transforms the platform pose relative to the world frame w . The matrix p T b i is a constant transformation to adjust the distance among the p and b i frames. Finally, q i contains the joint configuration of the manipulator i, and the matrix b i T e i represents the forward kinematics of manipulator i. The vector t r is defined for coordinated manipulation purposes, but we will talk about this in Section 3.
The pose of the mobile platform is described as
q 0 = x p y p θ p T
where x p and y p are the platform position and θ p its orientation. The matrix w T p can be defined as
w T p ( q 0 ) = cos ( θ p ) sin ( θ p ) 0 x p sin ( θ p ) cos ( θ p ) 0 y p 0 0 1 0 0 0 0 1
The constant matrix p T b i includes a rotation matrix p R b i and a translation vector p t b i to adjust the orientation and the position of frame b i relative to frame p . This transformation is shown below:
p T b i = p R b i p t b i 0 1
Figure 3 shows the coordinate frames assignment for the KUKA® Youbot® platform to obtain the matrices in (3). The frames b i and p are also included. Based on the provided specifications, the following matrices are established:
p T b 1 = 1 0 0 0.15 0 1 0 0 0 0 1 0.14 0 0 0 1 , p T b 2 = 1 0 0 0.15 0 1 0 0 0 0 1 0.14 0 0 0 1
The joint configuration of manipulator i is described as
q i = θ 1 i θ 2 i θ 3 i θ 4 i θ 5 i T
where θ j i represents the current joint value of the articulation j, where j = 1 , 2 , 3 , 4 , 5 . The forward kinematics b i T e i can be obtained based on the Denavit–Hartenberg (DH) model [5,34].
Figure 4 illustrates the coordinate frames’ assignment for the KUKA® Youbot® arm to obtain the DH table provided in Table 2. Each link j is represented by a homogeneous matrix j 1 T j , which transforms the frame attached to the link j 1 into the frame link j. The matrix j 1 T j is expressed as
j 1 T j = c θ j s θ j c α j s θ j s α j a j c θ j s θ j c θ j c α j c θ j s α j a j s θ j 0 s α j c α j d j 0 0 0 1
where θ j is a joint angle, a j is a link length, d j is a link offset, and α j is a link twist. For brevity, the s i n and c o s operations are represented with the letters s and c, respectively.
Considering the parameters in Table 2 and using (5), the following matrices can be obtained:
0 T 1 ( θ 1 ) = cos θ 1 0 sin θ 1 0.033 cos θ 1 sin θ 1 0 cos θ 1 0.033 sin θ 1 0 1 0 0.147 0 0 0 1 1 T 2 ( θ 2 ) = cos θ 2 sin θ 2 0 0.155 cos θ 2 sin θ 2 cos θ 2 0 0.155 sin θ 2 0 0 1 0 0 0 0 1 2 T 3 ( θ 3 ) = cos θ 3 sin θ 3 0 0.135 cos θ 3 sin θ 3 cos θ 3 0 0.135 sin θ 3 0 0 1 0 0 0 0 1 3 T 4 ( θ 4 ) = cos θ 4 0 sin θ 4 0 sin θ 4 0 cos θ 4 0 0 1 0 0 0 0 0 1 4 T 5 ( θ 5 ) = cos θ 5 sin θ 5 0 0 sin θ 5 cos θ 5 0 0 0 0 1 0.2175 0 0 0 1
Then, the forward kinematics b i T e i ( q i ) for each arm is calculated as
b i T e i ( q i ) = 0 T 5 ( q i ) = 0 T 1 ( θ 1 i ) 1 T 2 ( θ 2 i ) 2 T 3 ( θ 3 i ) 3 T 4 ( θ 4 i ) 4 T 5 ( θ 5 i )
Given an actual pose of the platform q 0 and a joint configuration of each manipulator q i , the forward kinematics of the mobile dual-arm system can be obtained as follows:
w T e i q 0 , q i = w T p q 0 p T b i b i T e i q i = w R e i w t e i 0 1
where w T e i q 0 , q i contains the position w t e i and orientation w R e i of the end-effector e i with respect to the world frame w .
The inverse kinematics of mobile dual-arm robots consists of computing the platform’s actual pose q 0 and the joint configurations q i given a desired end-effector pose w T e i for each manipulator. This work proposes an algorithm to solve the inverse kinematics of mobile dual-arm robots for cooperative manipulation tasks.

3. Description of the Proposed Approach

In a mobile dual-arm cooperative system, the manipulators can interact with each other to solve coordinated manipulation or work independently to solve non-coordinated tasks. Moreover, both manipulators perform the manipulation tasks on board the same mobile platform. Indeed, this complicates the kinematics analysis for both coordinated and non-coordinated manipulation. The inverse kinematics for mobile dual-arm systems cannot be solved independently due to both manipulators sharing the same platform pose. This paper addresses the case of coordinated manipulation. However, this approach can also be applied to solve non-coordinated tasks.
The proposal is based on the forward kinematic equations considering the two manipulators and the mobile platform. Considering all as a whole system, the inverse kinematics gives the system configuration no matter if it is a coordinated or a non-coordinated task. On the other hand, considering the manipulators independently, they cannot achieve their objective due to the interaction with the robotic platform.
Let us consider the mobile dual-arm robot presented in Figure 2. For coordinated manipulation, we considered that manipulator 1 has the role of master. Then, a vector t r is defined to compute the relative position of the end-effector e 2 expressed with respect to the frame e 1 . Then, we define the desired position t e 1 * for the end-effector of arm 1. The desired position t e 2 * for the end-effector of arm 2 is given by
t e 2 * = t e 1 * + t r
For non-coordinated manipulation, the desired position t e 2 * is provided independently of the desired position t e 1 * .

3.1. Objective Function Formulation

The aim of the proposed inverse kinematics algorithm is to minimize the error between the desired end-effector position of each arm and the actual end-effectors’ positions. Furthermore, it is considered to minimize the error between current and previous joints, including the mobile platform poses. This is useful to reduce the system motion, especially during coordinated trajectory tracking tasks.
The error between the desired position t e i * and the actual position w t e i of manipulator i can be computed as
e t i = t e i * w t e i
where · denotes the Euclidean norm. The position w t e i is obtained based on the forward kinematics (7) for the actual system configuration q 0 , q i .
To minimize the coordinated manipulation motion, we define errors between the actual configurations q 0 , q i and the previous configurations q 0 p r e v , q i p r e v . These errors are defined as
e q 0 = q 0 q 0 p r e v e q i = q i q i p r e v
The formulation of an objective function f, which includes the position and motion errors, is defined as
f = α e t 1 + e t 2 + β e q 0 + γ e q 1 + e q 2
where α , β , and γ are positive factors to scale the contribution of each term. The larger the value of α is, the higher the priority to minimize position errors. The larger the values of β are, the less movement for the mobile platform. Similarly, the larger the values of γ are, the less movement for the joints of each arm. These factors can be selected experimentally, but we recommend α > γ > β . That is, we provide higher priority to position errors, less motion for the manipulators, and much for the platform.

3.2. Inverse Kinematics Based on Metaheuristics Optimization Algorithms

We propose to solve the objective function (11) using metaheuristics algorithms. Most metaheuristics strategies are population-based optimization algorithms, where every member represents a potential solution. In this case, a population member contains a candidate configuration of the mobile dual-arm system. Moreover, metaheuristics algorithms require random initializations inside of a search space.
The joint rotation limits bound the search space of metaheuristics algorithms. The KUKA® Youbot® technical specifications provide the following upper q i u and lower q i u joint limits.
q 1 l = q 2 l = 169 65 150 102.5 167.5 T q 1 u = q 2 u = 169 90 146 102.5 167.5 T
The translations of the mobile platform and its rotation have no limits. However, we propose the following workspace to keep the platform movements bounded:
q 0 l = 1.5 m 1.5 m 180 T q 0 u = 1.5 m 1.5 m 180 T
where q 0 l and q 0 u are the lower and upper boundaries, respectively. All lower and upper boundaries are shown in degree values for clarity, although in the optimization process, the algorithms use radians. Then, we define the lower and upper boundaries of the whole mobile dual-arm system as q l = q 0 l T q 1 l T q 2 l T T and q u = q 0 u T q 1 u T q 2 u T T , respectively. These boundaries are needed to randomly initialize candidate solutions. Moreover, q l , q u R D , where D = 13 is the dimension of the optimization problem.
To generate random solutions, we propose to use the following equation:
q r = q l + q u q l r
where ⊙ indicates the elementwise product and r R D is a uniformly distributed random vector, where each element is in the range [ 0 , 1 ] . The random vector q r represents an initial solution for a candidate configuration.
The lower and upper boundaries also represent constraints that must be considered for real-world implementations. We considered solving the inverse kinematics of mobile dual-arm robots as a global constrained optimization problem, which is expressed as
arg min q f q , subject to q l < q < q u
where q defines the optimal configuration of the mobile dual-arm system with q = q 0 T q 1 T q 2 T T . The set of solutions that satisfy F = q : q l < q < q u is called the feasible solutions. In contrast, unfeasible solutions are given by F ¯ = q : q F . To deal with the constraints, we recalculated the vector q for those infeasible solutions using (12).

3.3. Coordinated Trajectory Tracking Algorithm

A path is divided into K points to solve coordinated trajectory tracking tasks. Every point k = 1 , 2 , 3 , , K becomes a desired position t k * for end-effector 1. The relative desired position for end-effector 2 is computed using (8). Then, the inverse kinematics is solved based on the optimization problem expressed in (13) to obtain an optimal configuration q k . The solution q k becomes the previous configuration for the next desired point t k + 1 * . The goal is to find the set of solutions Q = q 1 , q 2 , q 3 , , q K that define the trajectory tracking. A summary of the proposed coordinated trajectory tracking algorithm is given in Figure 5.

4. Experimental Results

The experiments aimed to test the performance of the proposed inverse kinematics of mobile dual-arm robots for cooperative manipulation. The considered tasks are coordinated inverse kinematics and coordinated trajectory tracking. The applicability of the proposed approach is demonstrated using the mobile dual-arm system based on the KUKA® Youbot® robot. Moreover, the tests were conducted in simulations and real-world experiments.
For the coordinated inverse kinematics tests, we propose to use the following desired positions.
Target point 1 : t r = 0.2 0.3 0.2 T t e 1 * = 0.5 0.2 0.45 T Target point 3 : t r = 0.2 0.5 0.1 T t e 1 * = 0.5 0.2 0.4 T Target point 2 : t r = 0.0 0.5 0.0 T t e 1 * = 0.3 0.2 0.5 T Target point 4 : t r = 0.0 0.3 0.2 T t e 1 * = 0.25 0.3 0.3 T
Four trajectories with different difficulty degrees are defined for coordinate trajectory tracking. Each trajectory was divided into K = 200 points. The vector t k * = x k y k z k T defines the k-th trajectory point. The trajectories are
Trajectory 1 : Sinusoidal x k = 0.5 z k = 0.4 + 0.05 sin 30 y k y k 0.25 , 0.75 Trajectory 3 : Trapezoidal x k = 0.5 r k = 0.45 + 0.1 sin 30 y k y k 0.25 , 0.75 z k = 0.5 if r k > 0.5 0.4 if r k < 0.4 r k otherwise Trajectory 2 : Circular x k = 0.5 y k = 0.25 + 0.05 cos θ k z k = 0.45 + 0.05 sin θ k θ k 0 , 2 π Trajectory 4 : Rose curve x k = 0.5 y k = 0.25 + r k cos θ k z k = 0.35 + r k sin θ k r k = 0.035 + 0.015 cos 3 θ k θ k 0 , 2 π
For all experiments, the parameter settings related to the objective function were selected as α = 1.2 , β = 0.1 , and γ = 0.4 . These values were selected experimentally, but we ensured that α > γ > β . Moreover, the following initial configurations were fixed as
q 0 p r e v = 0 0 π / 2 T q 1 p r e v = π / 2 π / 2 π / 4 π / 4 0 T q 2 p r e v = π / 2 π / 2 π / 4 π / 4 0 T
The performance of the proposed approach was analyzed and compared using the following metaheuristics algorithms: DE, CPABC, SDE, CS, QPSO, IMPSO, and CMA-ES. The comparisons were performed to find the algorithm that best minimizes the position and motion errors.
The parameter settings for the considered metaheuristics were conducted as follows: First, the common parameters were the population size of 30 members and a total of 1000 iterations. The particular parameter settings are given in Table 3.
The metaheuristics algorithms presented in Table 3 were considered for comparison purposes because they have been used previously in the literature to solve the inverse kinematics of fixed robotics manipulators, as reported in the following works [17,18,21,26,27,28,30].
In all experiments, the specifications of the test machine were an Intel Core i7-4770® (Intel i7 is a registered trademark of Intel Corporation USA) CPU 3.4 GHz and 16 GB of RAM. Moreover, the experiments were performed in the Matlab R2021a environment® (Matlab is a registered trademark of the MathWorks, Inc., USA).

4.1. Simulation Experiments for Coordinated Inverse Kinematics

This section presents a comparative analysis of different metaheuristics optimization algorithms for solving coordinated inverse kinematics tasks. The aim of the simulations was to identify those algorithms that best minimized the position errors e t 1 and e t 2 . The best algorithms are compared later in coordinated trajectory tracking tasks to analyze the motion error results.
For comparison purposes, every metaheuristic ran 100 times independently. To qualify the results, the statistical performance was measured with the mean, standard deviation (STD), and the best and worst results. The best algorithms report a small mean value with a low standard distribution, which is a small difference between the best and worst results. These measures are shown in tables, where the position error reported is e t 1 + e t 2 , which is given in meters (m).
In these tests, we considered that a coordinated inverse kinematics task is successfully solved if the reported position error result is less than 1 × 10 4 , which is an error below 0.1 mm. Then, a mean value below 1 × 10 4 indicates accurate results. Moreover, a low STD value indicates better precision. Additionally, the difference between the best and the worst measures shows the amount of dispersion related to the accuracy.
The coordinated inverse kinematics results are provided in Table 4, Table 5, Table 6 and Table 7. CMA-ES showed the highest precision and accuracy in all cases. It showed the lowest mean and STD values. It also showed the smallest worst measures. Clearly, CMA-ES outperformed the other algorithms. The performances of DE and SDE were quite similar. Their results were precise and accurate. DE and SDE stood out with all measured values below 1 × 10 4 . The worst results of Table 4, Table 5 and Table 6 indicated that SDE performed slightly better than DE. QPSO presented the best measure in Table 4. Moreover, IMPSO showed the bests measures in Table 5, Table 6 and Table 7. The performances of QPSO and IMPSO were similar, but not the best. All mean and STD measures of IMPSO were higher than 1 × 10 4 , which means low precision and accuracy. Table 7 indicates that QPSO also had low precision and accuracy. CS showed balanced results. The results were accurate even if they did not demonstrate the best mean and STD values. In all tests, those results are provided below 1 × 10 4 . CPABC performed poorly in all tests. It did not provide precise nor accurate results. In almost all cases, the measured values presented were above 1 × 10 4 .
Figure 6 illustrates the convergence curves of all compared algorithms. These results were the fitness convergence rates for the best position error results. The graphs show the first 300 iterations because posterior results did not report significant differences. As can be seen, the fastest convergence rates were given by CMA-ES. IMPSO also had fast convergence, as shown in Figure 6b–d. Moreover, the converge curves of DE, CS, CPABC, and SDE were similar. Finally, the slowest convergence rate was provided by QPSO.
Based on the results of these tests, we noticed that CMA-ES outperformed the other algorithms. It showed the highest accuracy and precise results with faster convergence rates. Moreover, the performances of DE and SDE were also remarkable. The performance of CS stood out over IMPSO, QPSO, and CPABC. Finally, the IMPSO, QPSO, and CPABC algorithms were not considered for further comparison tests because of their poor performance.

4.2. Simulation Experiments for Coordinated Trajectory Tracking

This section presents the simulation results for coordinated trajectory tracking tasks. We compared the performance of the metaheuristics algorithms that best performed in the coordinated inverse kinematics tests. The compared algorithms were DE, SDE, CS, and CMA-ES. We were interested in finding the algorithm that best minimized the position errors e t 1 and e t 2 , but also presented minimum motion errors e q 0 , e q 1 , and e q 2 . The best algorithm was used for the real-world implementations.
For the comparison analysis, the position errors are reported as e t 1 + e t 2 and the motion errors as e q 0 + e q 1 + e q 2 . We used boxplots to graphically show the statistical variation of the inverse kinematics results related to each point in the trajectory. The best algorithms show a small data dispersion with a low median value. In addition, these results should present the fewest outliers.
In these simulations, the position and motion errors were compared using boxplots. To qualify the position error results, the statistical performance was measured with the mean, STD, and min and max value results. Moreover, the motion errors are illustrated with graphs to visually analyze the motion during the training tasks. Additionally, the desired trajectory and the actual trajectory provided by the optimization algorithms are also compared with graphs. Finally, each metaheuristics algorithm used a total of 300 iterations.
The position error results of the coordinated trajectory tasks are given in Figure 7. Clearly, CS showed the worst results. It had a larger data dispersion with the presence of outliers. In all cases, the reported median value was around 0.01 m, which is not adequate for trajectory tracking. Moreover, it seems that DE, SDE, and CMAES performed similarly. They provided a small data dispersion with lower median values. However, these results are analyzed in tables for a fair comparison. Such results are given in Table 8, Table 9, Table 10 and Table 11.
Based on the results provided in Table 8, Table 9, Table 10 and Table 11, we noticed that the CMA-ES algorithm outperformed the others. It had the best mean, STD, and min and max results. These demonstrated that CMA-ES provided accurate and precise coordinate tracking results. DE and SDE also provided acceptable results with high accuracy and precision. They performed similarly in all cases, with measures below 1 × 10 4 . The performance of CS was poor. All reported measures were bigger than 1 × 10 4 , which demonstrated low accuracy and precision.
To visually see the differences in the position errors between CMA-ES and SDE, we considered including trajectory tracking graphs. The coordinated trajectory tracking results are provided in Figure 8. These results illustrate the successful trajectory tracking for all tests. As can be seen, the CMA-ES results fit perfectly in all given trajectories. Moreover, CMA-ES performed better than SDE. However, both algorithms provided excellent results.
The motion error results from the coordinate trajectory tracking tasks are given in Figure 9. As expected, CS reported the worst results. It had the largest data dispersion with the presence of outliers in all tests. In contrast, DE, SDE, and CMA-ES performed similarly. Their data dispersion was small for the results in the sinusoidal, circular, and rose curve trajectories; see Figure 9a, Figure 9b, and Figure 9d, respectively. Moreover, their results in Figure 9c indicated that the trapezoidal trajectory was more difficult to solve since more movement is required to follow the trajectory. Indeed, we considered including motion comparison graphs to analyze the performance of CMA-ES against CS for the trapezoidal trajectory. We did not consider including DE nor SDE for comparison because they performed similarly.
Figure 10 shows the motion results for the coordinate trapezoidal tracking. We compared the performance of CMA-ES against CS to emphasize the need for small motion errors. As we can see, CMA-ES showed smooth tracking results. In contrast, CS presented discontinuous motions. In real-world applications, it is important to avoid these rough motions since they can seriously damage and wear out the joints.
Based on the presented results, the CMAES algorithm was the most reliable method to solve coordinated trajectory tracking tasks. However, the DE and SDE algorithms are also recommended.

4.3. Real-World Experiments for Coordinated Trajectory Tracking

In this section, we are interested in presenting the applicability of the proposed approach in a real-world implementation. We propose to solve coordinated trajectory tracking based on the CMA-ES algorithm. The applicability was demonstrated using the KUKA® Youbot® system; see Figure 1.
The experiments were performed using the Robot Operating System (ROS) toolbox for Matlab. There exists an ROS component to access the KUKA® Youbot® hardware. This component provides a PID algorithm to control the joint positions of each manipulator. Moreover, this component also provides the current state of the joints based on encoder measures, and the current pose is given by odometry. To control the mobile platform pose, we used an adaptive PID scheme [35].
The coordinated trapezoidal trajectory task was considered for this test. The optimal solution found by CMA-ES represented a reference configuration q * . Indeed, we had a reference for the platform q 0 * , a joint reference configuration for manipulator 1 q 1 * , and a reference for manipulator 2 q 2 * .
The presented results in this test were the comparative motion results between the reference and actual system configuration and the coordinated trajectory tracking results.
The motion control results for the mobile platform are given in Figure 11. Moreover, the motion control results for manipulator 1 and manipulator 2 are given in Figure 12 and Figure 13, respectively. For some of the first reference values, there was a greater following error. However, after the control laws reached the references, the following error was minimal. The reported results suggested that the reference and the actual values were practically the same. If the current system configuration were the same as the reference values, then the coordinate trajectory tracking should succeed.
The coordinated trajectory tracking results are provided in Figure 14. As can be seen, both manipulators on board the same mobile platform succeeded in following the references as expected. We noticed that there were bigger tracking errors at the beginning of the trajectory, but this is normal since the actual position related to the initial system configuration was not close to the first reference point. When the control algorithm reached the reference, both trajectories were practically the same. We concluded that the coordinated trapezoidal tracking was successful.

5. Discussion

Gradient-based optimization algorithms are used to compute the minimum of a differentiable function. In the presence of multiple minima, these approaches may fail to find a global minimum. On the other hand, metaheuristics algorithms achieve global solutions, and the definition of the objective function does not necessarily have to be differentiable [36]. Metaheuristics algorithms are commonly used to solve the inverse kinematics of robotic manipulators. In this work, we proposed to solve the inverse kinematics of mobile dual-arm robots for coordinated manipulation. We considered including a comparative analysis among DE, CPABC, SDE, CS, QPSO, IMPSO, and CMA-ES to solve the inverse kinematics problems.
The comparative analyses indicated that CMA-ES outperformed the other algorithms with the highest accuracy and precise results. In the coordinated inverse kinematics tests, CMA-ES reported the smallest position error results with values below 1 × 10 12 m. In the coordinated trajectory tracking tests, CMA-ES also reported the smallest position error results with values below 1 × 10 8 m. In both tests, it also reported the smallest STD values and fastest convergence rates. Additionally, CMA-ES showed a minimal motion error, which is a smooth movement during trajectory tracking. For these reasons, we considered the CMA-ES algorithm the most reliable method for solving coordinated manipulation tasks.
The comparative analyses also indicated that DE and SDE stood out in both the coordinated inverse kinematics and coordinated trajectory tracking tests. Their performances were similar with position error values below 1 × 10 5 m in both tests. Their STD values results were also remarkable. DE and SDE provided accurate and precise results with low movement errors.
The performance of CS was quite good in the coordinated inverse kinematics tasks, but its performance was poor in coordinated trajectory tracking. It seems that CS required more iterations to improve its performance. Moreover, the performance of CPABC, QPSO, and IMPSO was poor in both tests. The performance of these algorithms can be improved by carefully modifying their parameter settings. We concluded that these algorithms are not convenient to solve coordinated manipulation tasks.
Closed-form solutions give exact solutions for simple systems; for complex systems, they do not ensure a solution. In this case, the use of iterative methods is advised, which gives an approximate solution. The small position errors provided by the CMA-ES approach indicate highly precise results. It is important to note that such results are achieved in simulations. However, a position error of less than 1 × 10 12 meters is difficult to achieve in real-world experiments due to hardware limitations. The use of industrial robots with the capability of high precision is required. Moreover, macro-robots are often used for medical proposes, which can achieve highly precise positions [37].
Although the proposed algorithm focuses on solving coordinate manipulation problems, this approach can also be applied to solve non-coordinated tasks. In non-coordinated manipulation, it is required to provide two independent inverse kinematics targets. The users need to provide the values of t e 1 * and t e 2 * independently. The rest of the inverse kinematics algorithm is practically the same.
This paper introduced a kinematic model for mobile dual-arm robots, using as the case of study the KUKA® Youbot® system. This system is composed of two 5-DOF manipulators attached to a 3-DOF omnidirectional platform. However, it is important to remark that the proposed scheme is not limited to this system; other manipulator configurations can be used to replace the ones used in this work. Since the forward kinematics is based on the DH model, no modifications to the inverse kinematics algorithm are required.
The proposed approach only considers the kinematic analysis to compute the mobile platform pose and the joint configuration of each arm to reach their desired end-effector position. Since the proposed approach is based on the forward kinematics equations, then the dynamical analysis is not required. Moreover, the optimal obtained configuration by the proposal was used as a reference for control purposes. Then, control strategies based on dynamic analysis can be used to control the system. Since the proposed approach computes the mobile and manipulators’ references, the control strategies can be implemented independently, with the advantage that the dynamic analysis of the complete system is not required.
To show the applicability of the proposed approach, real-world experiments were performed using the mobile dual-arm KUKA® Youbot® system to solve a coordinated trajectory tracking task. Moreover, we used a generic PID algorithm to control each manipulator’s joint position and an adaptive neuron PID to control the mobile platform pose. The reported results showed that the error references were close to zero, which implies that the cooperative task was successful.
Additional objectives in the optimization problems to solve the inverse kinematics of robotic manipulators have been proposed in recent years. Repulsive potential fields can be considered in the formulation of the objective function to deal with collision avoidance [38]. The use of the penalty function can also be used to handle joint limit constraints [29,30]. Moreover, the combination of metaheuristics algorithms and artificial neural networks provides the capacity to reduce time consumption [39,40]. Indeed, the use of recurrent neuronal networks is an appealing topic to deal with real-time inverse kinematics, and this has been proven to solve the control of redundant manipulators [41].
As a final remark, metaheuristics algorithms are often used for offline applications because they are time-consuming. However, the use of dedicated hardware such as the NVIDIA CUDA parallel architecture presents an interesting framework to significantly reduce time consumption, which is appealing for online and real-time applications [42].

6. Conclusions

This work introduced an approach for solving the inverse kinematics of mobile dual-arm robots for cooperative manipulation. Simulation and real-world experiments were performed to prove the effectiveness of the proposed approach for solving coordinated inverse and coordinated trajectory tracking tasks. Moreover, to solve the inverse kinematics, we used metaheuristics optimization algorithms. Then, comparative analyses were performed among the DE, CPABC, SDE, CS, QPSO, IMPSO, and CMA-ES algorithms. The experimental setup considered a mobile dual-arm system based on the KUKA® Youbot® system, which is composed of two 5-DOF manipulators attached to a 3-DOF omnidirectional platform.
Based on the comparative results, we can conclude that CMA-ES outperformed the other algorithms in all experiments. It reported the highest accuracy and precise results with the fastest convergence rates for coordinated inverse kinematics tasks. CMA-ES also provided the smoothest joint motions during coordinated trajectory tracking tasks. The performance of DE and SDE was also remarkable. They performed similarly in all tests with high accuracy and precision. They also provided smooth joint motions. CS performed better than CPABC, QPSO, and IMPSO in coordinated inverse kinematics tasks. However, it is not recommended for coordinated trajectory tracking due to its high motion errors. The CPABC, QPSO, and IMPSO algorithms are not recommended to solve the inverse kinematics of mobile dual-arm robots.
Additionally, the CMA-ES algorithm was tested for coordinated trajectory tracking in real-world experiments. The obtained optimal configurations were used as references. Then, ROS components were used to control the system. Since the references and the actual robot configuration perfectly matched, the results proved the applicability of the proposed approach.
Although the proposed approach focuses on solving coordinated inverse kinematics and coordinated trajectory tracking tasks, it can be implemented to solve non-coordinated manipulation as well. In future research, this work can be extended to solve the inverse kinematics of mobile dual-arm robots with non-holonomic platforms. Additionally, we propose to design a control scheme based on the dynamic model for the manipulator and the mobile platform to reach the references provided by the presented proposed approach.
The presented kinematic model considers an omnidirectional platform. It is appealing to propose an approach for mobile dual-arm robots with differential-drive or car-like platforms. However, the inverse kinematics approach must consider the non-holonomic constraints. We leave this approach for future research.

Author Contributions

Conceptualization, J.H.-B., C.L.-F. and G.M.-S.; data curation, J.D.R. and G.M.-S.; funding acquisition, A.Y.A.; investigation and software, J.D.R. and G.M.-S.; methodology, J.H.-B. and C.L.-F.; project administration and supervision, A.Y.A.; validation, J.H.-B. and C.L.-F.; visualization and writing, J.H.-B., J.D.R. and A.Y.A. All authors read and agreed to the published version of the manuscript.

Funding

This research was supported by CONACYT Mexico, through Project FOP16-2021-01-319619.

Data Availability Statement

The data analyzed are available from the authors upon request.

Acknowledgments

The authors also thank Universidad de Guadalajara for their support in this research.

Conflicts of Interest

The authors declare no conflict of interest.

Abbreviations

The following abbreviations are used in this manuscript:
DOFsDegrees of freedom
STDStandard deviation
DEDifferential evolution
CPABCChaotic and parallelized artificial bee colony
SDESelf-adaptive differential evolution
CSCuckoo search
QPSOQuantum particle swarm optimization
IMPSOImproved particle swarm optimization
CMA-ESCovariance matrix adaptation evolution strategy

References

  1. Freddi, A.; Longhi, S.; Monteriù, A.; Ortenzi, D. Redundancy analysis of cooperative dual-arm manipulators. Int. J. Adv. Robot. Syst. 2016, 13, 1729881416657754. [Google Scholar] [CrossRef]
  2. Smith, C.; Karayiannidis, Y.; Nalpantidis, L.; Gratal, X.; Qi, P.; Dimarogonas, D.V.; Kragic, D. Dual arm manipulation—A survey. Robot. Auton. Syst. 2012, 60, 1340–1353. [Google Scholar] [CrossRef] [Green Version]
  3. Stifter, S. Algebraic methods for computing inverse kinematics. J. Intell. Robot. Syst. 1994, 11, 79–89. [Google Scholar] [CrossRef]
  4. Lee, C.; Ziegler, M. Geometric Approach in Solving Inverse Kinematics of PUMA Robots. IEEE Trans. Aerosp. Electron. Syst. 1984, AES-20, 695–706. [Google Scholar] [CrossRef]
  5. Siciliano, B.; Lorenzo Sciavicco, L.V. Robotics-Modelling, Planning and Control, 2nd ed.; Advanced Textbooks in Control and Signal Processing; Springer: Berlin/Heidelberg, Germany, 2008. [Google Scholar]
  6. Ortenzi, D.; Muthusamy, R.; Freddi, A.; Monteriù, A.; Kyrki, V. Dual-arm cooperative manipulation under joint limit constraints. Robot. Auton. Syst. 2018, 99, 110–120. [Google Scholar] [CrossRef] [Green Version]
  7. Jamisola, R.S.; Roberts, R.G. A more compact expression of relative Jacobian based on individual manipulator Jacobians. Robot. Auton. Syst. 2015, 63, 158–164. [Google Scholar] [CrossRef]
  8. Alkayyali, M.; Tutunji, T.A. PSO-based Algorithm for Inverse Kinematics Solution of Robotic Arm Manipulators. In Proceedings of the 2019 20th International Conference on Research and Education in Mechatronics (REM), Wels, Austria, 23–24 May 2019; pp. 1–6. [Google Scholar]
  9. Abainia, K.; Ben Ali, Y.M. Bio-inspired Approach for Inverse Kinematics of 6-DOF Robot Manipulator with Obstacle Avoidance. In Proceedings of the 2018 3rd International Conference on Pattern Analysis and Intelligent Systems (PAIS), Tebessa, Algeria, 24–25 October 2018; pp. 1–8. [Google Scholar]
  10. Umar, A.; Shi, Z.; Wang, W.; Farouk, Z.I.B. A Novel Mutating PSO Based Solution for Inverse Kinematic Analysis of Multi Degree-of-Freedom Robot Manipulators. In Proceedings of the 2019 IEEE International Conference on Artificial Intelligence and Computer Applications (ICAICA), Dalian, China, 29–31 March 2019; pp. 459–463. [Google Scholar]
  11. Wang, M.; Luo, J.; Yuan, J.; Walter, U. Coordinated trajectory planning of dual-arm space robot using constrained particle swarm optimization. Acta Astronaut. 2018, 146, 259–272. [Google Scholar] [CrossRef]
  12. Tam, B.; 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] [CrossRef]
  13. Nguyen, T.T.; Nguyen, V.H.; Nguyen, X.H. Comparing the Results of Applying DE, PSO and Proposed Pro DE, Pro PSO Algorithms for Inverse Kinematics Problem of a 5-DOF Scara Robot. In Proceedings of the 2020 International Conference on Advanced Mechatronic Systems (ICAMechS), Hanoi, Vietnam, 10–13 December 2020; pp. 45–49. [Google Scholar]
  14. Nizar, I.I. Investigation of Inverse kinematics Solution for a Human-like Aerial Manipulator Based on The Metaheuristic Algorithms. In Proceedings of the 2019 International Seminar on Electron Devices Design and Production (SED), Prague, Czech Republic, 23–24 April 2019; pp. 1–13. [Google Scholar]
  15. Kumar, A.; Banga, V.K.; Kumar, D.; Yingthawornsuk, T. Kinematics Solution using Metaheuristic Algorithms. In Proceedings of the 2019 15th International Conference on Signal-Image Technology and Internet-Based Systems (SITIS), Sorrento-Naples, Italy, 26–29 November 2019; pp. 505–510. [Google Scholar]
  16. Dereli, S.; Koker, 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] [Green Version]
  17. Abdor-Sierra, J.A.; Merchán-Cruz, E.A.; Rodríguez-Cañizo, R.G. A comparative analysis of metaheuristic algorithms for solving the inverse kinematics of robot manipulators. Results Eng. 2022, 16, 100597. [Google Scholar] [CrossRef]
  18. 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]
  19. Nguyen, T.; Bui, T.; Pham, H. Using proposed optimization algorithm for solving inverse kinematics of human upper limb applying in rehabilitation robotic. Artif. Intell. Rev. 2022, 55, 679–705. [Google Scholar] [CrossRef]
  20. Dereli, S.; Koker, R. A meta-heuristic proposal for inverse kinematics solution of 7-DOF serial robotic manipulator: Quantum behaved particle swarm algorithm. Artif. Intell. Rev. 2020, 53, 949–964. [Google Scholar] [CrossRef]
  21. Zhang, L.; Xiao, N. A novel artificial bee colony algorithm for inverse kinematics calculation of 7-DOF serial manipulators. Soft Comput. 2019, 23, 3269–3277. [Google Scholar] [CrossRef]
  22. Larsen, L.; Kim, J. Path planning of cooperating industrial robots using evolutionary algorithms. Robot.-Comput.-Integr. Manuf. 2021, 67, 102053. [Google Scholar] [CrossRef]
  23. Liu, F.; Huang, H.; Li, B.; Xi, F. A parallel learning particle swarm optimizer for inverse kinematics of robotic manipulator. Int. J. Intell. Syst. 2021, 36, 6101–6132. [Google Scholar] [CrossRef]
  24. Šegota, S.B.; Anđelić, N.; Lorencin, I.; Saga, M.; Car, Z. Path planning optimization of six-degree-of-freedom robotic manipulators using evolutionary algorithms. Int. J. Adv. Robot. Syst. 2020, 17, 1729881420908076. [Google Scholar]
  25. Li, C.; Dong, H.; Li, X.; Zhang, W.; Liu, X.; Yao, L.; Sun, H. Inverse Kinematics Study for Intelligent Agriculture Robot Development via Differential Evolution Algorithm. In Proceedings of the 2021 International Conference on Computer, Control and Robotics (ICCCR), Shanghai, China, 8–10 January 2021; pp. 37–41. [Google Scholar]
  26. Karahan, O.; Karci, H.; Tangel, A. Optimal trajectory generation in joint space for 6R industrial serial robots using cuckoo search algorithm. Intell. Serv. Robot. 2022, 15, 627–648. [Google Scholar] [CrossRef]
  27. Lopez-Franco, C.; Hernandez-Barragan, J.; Alanis, A.Y.; Arana-Daniel, N. A soft computing approach for inverse kinematics of robot manipulators. Eng. Appl. Artif. Intell. 2018, 74, 104–120. [Google Scholar] [CrossRef]
  28. 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] [Green Version]
  29. Hernández-Barragán, J.; López-Franco, C.; Alanis, A.Y.; Arana-Daniel, N.; López-Franco, M. Dual-arm cooperative manipulation based on differential evolution. Int. J. Adv. Robot. Syst. 2019, 16, 1729881418825188. [Google Scholar] [CrossRef]
  30. Hernandez-Barragan, J.; Lopez-Franco, C.; Arana-Daniel, N.; Alanis, A.Y. Inverse kinematics for cooperative mobile manipulators based on self-adaptive differential evolution. PeerJ Comput. Sci. 2021, 7, e419. [Google Scholar] [CrossRef] [PubMed]
  31. 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]
  32. Li, Z.; Yang, C.; Su, C.; Deng, J.; Zhang, W. Vision-Based Model Predictive Control for Steering of a Nonholonomic Mobile Robot. IEEE Trans. Control. Syst. Technol. 2016, 24, 553–564. [Google Scholar] [CrossRef]
  33. Bischoff, R.; Huggenberger, U.; Prassler, E. KUKA youBot - a mobile manipulator for research and education. In Proceedings of the 2011 IEEE International Conference on Robotics and Automation, Shanghai, China, 9–13 May 2011; pp. 1–4. [Google Scholar]
  34. Spong, M.W.; Vidyasagar, M. Robot Dynamics and Control; John Wiley & Sons: Hoboken, NJ, USA, 2008. [Google Scholar]
  35. Hernandez-Barragan, J.; Rios, J.D.; Alanis, A.Y.; Lopez-Franco, C.; Gomez-Avila, J.; Arana-Daniel, N. Adaptive Single Neuron Anti-Windup PID Controller Based on the Extended Kalman Filter Algorithm. Electronics 2020, 9, 636. [Google Scholar] [CrossRef]
  36. Simon, D. Evolutionary Optimization Algorithms; John Wiley & Sons: Hoboken, NJ, USA, 2013. [Google Scholar]
  37. Sun, Y.; Nelson, B.J. Biological Cell Injection Using an Autonomous MicroRobotic System. T Int. J. Robot. Res. 2002, 21, 861–868. [Google Scholar] [CrossRef]
  38. Gai, S.N.; Sun, R.; Chen, S.J.; Ji, S. 6-DOF Robotic Obstacle Avoidance Path Planning Based on Artificial Potential Field Method. In Proceedings of the 2019 16th International Conference on Ubiquitous Robots (UR), Jeju, Korea, 24–27 June 2019; pp. 165–168. [Google Scholar]
  39. Khan, A.H.; Li, S.; Cao, X. Tracking control of redundant manipulator under active remote center-of-motion constraints: An RNN-based metaheuristic approach. Sci. China Inf. Sci. 2021, 64, 132203. [Google Scholar] [CrossRef]
  40. Wang, J.; Zhang, Y. Recurrent neural networks for real-time computation of inverse kinematics of redundant manipulators. In Machine Intelligence: Quo Vadis? World Scientific: Singapore, 2004; pp. 299–319. [Google Scholar]
  41. Xie, Z.; Jin, L.; Luo, X. Kinematics-Based Motion-Force Control for Redundant Manipulators with Quaternion Control. IEEE Trans. Autom. Sci. Eng. 2022, 1–14. [Google Scholar] [CrossRef]
  42. Fabris, F.; Krohling, R.A. A co-evolutionary differential evolution algorithm for solving min–max optimization problems implemented on GPU using C-CUDA. Expert Syst. Appl. 2012, 39, 10324–10333. [Google Scholar] [CrossRef]
Figure 1. Mobile dual-arm system KUKA® Youbot®. It is composed of two 5-DOF manipulators and a 3-DOF mobile platform.
Figure 1. Mobile dual-arm system KUKA® Youbot®. It is composed of two 5-DOF manipulators and a 3-DOF mobile platform.
Mathematics 10 04135 g001
Figure 2. Kinematic chain of the mobile dual-arm system based on the KUKA® Youbot® robot.
Figure 2. Kinematic chain of the mobile dual-arm system based on the KUKA® Youbot® robot.
Mathematics 10 04135 g002
Figure 3. Coordinate frames assignment for the KUKA® Youbot® mobile platform based on the technical specifications manual.
Figure 3. Coordinate frames assignment for the KUKA® Youbot® mobile platform based on the technical specifications manual.
Mathematics 10 04135 g003
Figure 4. Coordinate frames’ assignment for the KUKA® Youbot® manipulator based on the technical specifications manual.
Figure 4. Coordinate frames’ assignment for the KUKA® Youbot® manipulator based on the technical specifications manual.
Mathematics 10 04135 g004
Figure 5. Coordinated trajectory tracking algorithm.
Figure 5. Coordinated trajectory tracking algorithm.
Mathematics 10 04135 g005
Figure 6. Convergencecurves’ results. The results for the best position errors are presented.
Figure 6. Convergencecurves’ results. The results for the best position errors are presented.
Mathematics 10 04135 g006
Figure 7. Position error results of coordinated trajectory tracking tests.
Figure 7. Position error results of coordinated trajectory tracking tests.
Mathematics 10 04135 g007
Figure 8. Coordinated trajectory tracking comparative results. The compared algorithms are CMA-ES and SDE. The “Desired” label means the desired end-effector trajectory.
Figure 8. Coordinated trajectory tracking comparative results. The compared algorithms are CMA-ES and SDE. The “Desired” label means the desired end-effector trajectory.
Mathematics 10 04135 g008
Figure 9. Motion error results of coordinated trajectory tracking tests.
Figure 9. Motion error results of coordinated trajectory tracking tests.
Mathematics 10 04135 g009
Figure 10. Joint motion comparative results for coordinated trapezoidal tracking. The compared algorithms are CMA-ES and CS.
Figure 10. Joint motion comparative results for coordinated trapezoidal tracking. The compared algorithms are CMA-ES and CS.
Mathematics 10 04135 g010
Figure 11. Motion results for the mobile platform. The “Reference” label indicates the optimal pose value provided by the CMA-ES algorithm, and the “Measured” label is the current odometry value.
Figure 11. Motion results for the mobile platform. The “Reference” label indicates the optimal pose value provided by the CMA-ES algorithm, and the “Measured” label is the current odometry value.
Mathematics 10 04135 g011
Figure 12. Motion result for manipulator 1. The “Reference” label indicates the optimal joint value provided by the CMA-ES algorithm, and the “Measured” label is the current measurement.
Figure 12. Motion result for manipulator 1. The “Reference” label indicates the optimal joint value provided by the CMA-ES algorithm, and the “Measured” label is the current measurement.
Mathematics 10 04135 g012
Figure 13. Motion result for manipulator 2. The “Reference” label indicates the optimal joint value provided by the CMA-ES algorithm, and the “Measured” label is the current measurement.
Figure 13. Motion result for manipulator 2. The “Reference” label indicates the optimal joint value provided by the CMA-ES algorithm, and the “Measured” label is the current measurement.
Mathematics 10 04135 g013
Figure 14. Coordinated trajectory tracking results. The “Reference” label represents the trajectory achieved by the CMA-ES algorithm, and the “Measured” label is the current end-effector position.
Figure 14. Coordinated trajectory tracking results. The “Reference” label represents the trajectory achieved by the CMA-ES algorithm, and the “Measured” label is the current end-effector position.
Mathematics 10 04135 g014
Table 1. State-of-the-art literature review. IK means inverse kinematics.
Table 1. State-of-the-art literature review. IK means inverse kinematics.
ReferenceMetaheuristicsRobotic SystemApplication
[16]ABC7-DOF manipulatorIK solutions
[17]PSO, DE, QPSO, IMPSO6-DOF and 7-DOF manipulatorsIK solutions
[18]IMPSO6-DOF manipulatorIK solutions
[19]ISADE7-DOF manipulatorIK solutions
[20]QPSO7-DOF manipulatorIK solutions
[21]CPABC7-DOF manipulatorIK solutions
[22]EA14-DOF dual-armPath planning
[23]PLPSO6-DOF manipulatorIK solutions
[24]GA, DE6-DOF manipulatorPath planning
[25]DE7-DOF manipulatorIK solutions
[26]CS6-DOF manipulatorPath planning
Table 2. DH table for the KUKA® Youbot® manipulator.
Table 2. DH table for the KUKA® Youbot® manipulator.
Linka (m) α (rad)d (m) θ (rad)
10.033 π / 2 0.147 θ 1
20.15500 θ 2
30.13500 θ 3
40 π / 2 0 θ 4
5000.2175 θ 5
Table 3. Parameter settings in state-of-the-art literature review.
Table 3. Parameter settings in state-of-the-art literature review.
ReferenceAlgorithmParameter Settings
[28]DEDE/rand/1/bin, F = 0.6 , C R = 0.9
[21]CPABCLimits L = 40 , M R = 0.8 , S F = 0.6
[30]SDE F = 0.5 , C R = 0.8
[26]CSDiscover rate P = 0.25
[20]QPSO β 0 = 0.5 , β 1 = 1.0
[17]IMPSO w i = 0.2 , 0.4 , 0.6 , 0.8 , 1.0 , 1.2 , 1.4 , 1.6 , 1.8 , 2.0 , C 1 = 1.4962 , C 2 = 1.4962
[27]CMAESStandard ( μ , λ ) -CMA-ES, λ = 30
Table 4. Position error results for target point 1. The best results are highlighted in bold.
Table 4. Position error results for target point 1. The best results are highlighted in bold.
DECPABCSDECSQPSOIMPSOCMA-ES
Mean5.136 × 10 6 0.0220315.440 × 10 7 0.000131830.00088520.0018518 7.965 × 10 15
STD2.360 × 10 5 0.0979281.193 × 10 6 6.929 × 10 5 0.00374550.0084942 1.509 × 10 14
Best7.488 × 10 9 1.717 × 10 15 3.683 × 10 9 2.513 × 10 5 6.245 × 10 17 8.370 × 10 17 6.973 × 10 16
Worst0.000166890.584876.887 × 10 6 0.00032290.0227340.055906 1.03 × 10 13
Table 5. Position error results for target point 2. The best results are highlighted in bold.
Table 5. Position error results for target point 2. The best results are highlighted in bold.
DECPABCSDECSQPSOIMPSOCMA-ES
Mean1.036  × 10 5 0.000518082.768  × 10 6 0.00035660.00029910.0062474 3.803 × 10 13
STD2.287  × 10 5 0.00185155.428  × 10 6 0.000210110.000992980.035237 1.469 × 10 12
Best1.257  × 10 8 7.467  × 10 15 1.049  × 10 8 9.012  × 10 5 1.875  × 10 13 1.746 × 10 16 4.616 × 10 16
Worst0.000109990.0117153.109  × 10 5 0.00101760.00624290.24645 8.107 × 10 12
Table 6. Position error results for target point 3. The best results are highlighted in bold.
Table 6. Position error results for target point 3. The best results are highlighted in bold.
DECPABCSDECSQPSOIMPSOCMA-ES
Mean8.119  × 10 6 0.00363932.754  × 10 6 0.000268860.00025420.0034882 8.839 × 10 13
STD1.843  × 10 5 0.0216615.134  × 10 6 0.000167980.0012580.020727 2.685 × 10 12
Best5.514  × 10 8 7.992  × 10 15 2.743  × 10 8 3.107  × 10 5 1.257  × 10 13 2.310 × 10 16 1.994  × 10 15
Worst0.000110670.153162.599  × 10 5 0.000743170.00859170.14618 1.523 × 10 11
Table 7. Position error results for target point 4. The best results are highlighted in bold.
Table 7. Position error results for target point 4. The best results are highlighted in bold.
DECPABCSDECSQPSOIMPSOCMA-ES
Mean4.213  × 10 6 0.028323.229  × 10 6 0.000436250.0232820.040247 8.710 × 10 14
STD5.632 × 10 6 0.0871431.264  × 10 5 0.000284180.0159850.09733 2.608 × 10 13
Best8.997  × 10 8 1.023  × 10 15 1.919  × 10 9 5.754  × 10 5 5.658  × 10 12 7.850 × 10 17 8.01  × 10 16
Worst2.941  × 10 5 0.399838.697  × 10 5 0.00141470.0648590.4156 1.488 × 10 12
Table 8. Position error results for sinusoidal trajectory. The best results are highlighted in bold.
Table 8. Position error results for sinusoidal trajectory. The best results are highlighted in bold.
DESDECSCMA-ES
Mean5.104  × 10 5 5.5523  × 10 5 0.0099478 1.1142 × 10 8
STD7.5244  × 10 5 3.94  × 10 5 0.0055781 2.9257 × 10 8
Min6.0195  × 10 6 4.3216  × 10 6 0.0028493 2.6832 × 10 13
Max0.000879220.000265860.036553 3.7112 × 10 7
Table 9. Position error results for circular trajectory. The best results are highlighted in bold.
Table 9. Position error results for circular trajectory. The best results are highlighted in bold.
DESDECSCMA-ES
Mean4.0829  × 10 5 5.2769  × 10 5 0.009863 3.4473 × 10 9
STD2.9189  × 10 5 3.8536  × 10 5 0.0046131 6.085 × 10 9
Min3.7308  × 10 6 6.9321  × 10 6 0.0025768 3.7374 × 10 15
Max0.000215410.00024040.027738 4.8502 × 10 8
Table 10. Position error results for trapezoidal trajectory. The best results are highlighted in bold.
Table 10. Position error results for trapezoidal trajectory. The best results are highlighted in bold.
DESDECSCMA-ES
Mean4.1641  × 10 5 4.6393  × 10 5 0.010247 7.3893 × 10 9
STD3.4045  × 10 5 3.4973  × 10 5 0.0047796 2.0364 × 10 8
Min4.1663  × 10 6 5.7924  × 10 6 0.0015987 3.4801 × 10 16
Max0.000242290.000198330.030391 1.2199 × 10 7
Table 11. Position error results for rose curve trajectory. The best results are highlighted in bold.
Table 11. Position error results for rose curve trajectory. The best results are highlighted in bold.
DESDECSCMA-ES
Mean3.5829  × 10 5 4.2613  × 10 5 0.0092417 2.3824 × 10 9
STD2.8703  × 10 5 2.9939  × 10 5 0.0048608 3.9706 × 10 9
Min5.3653  × 10 6 4.1256  × 10 6 0.0014107 3.6486 × 10 12
Max0.00019640.000183270.031768 2.4175 × 10 8
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

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. https://doi.org/10.3390/math10214135

AMA Style

Hernandez-Barragan J, Martinez-Soltero G, Rios JD, Lopez-Franco C, Alanis AY. A Metaheuristic Optimization Approach to Solve Inverse Kinematics of Mobile Dual-Arm Robots. Mathematics. 2022; 10(21):4135. https://doi.org/10.3390/math10214135

Chicago/Turabian Style

Hernandez-Barragan, Jesus, Gabriel Martinez-Soltero, Jorge D. Rios, Carlos Lopez-Franco, and Alma Y. Alanis. 2022. "A Metaheuristic Optimization Approach to Solve Inverse Kinematics of Mobile Dual-Arm Robots" Mathematics 10, no. 21: 4135. https://doi.org/10.3390/math10214135

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