Next Article in Journal
Hyperchaotic Maps and the Single Neuron Model: A Novel Framework for Chaos-Based Image Encryption
Previous Article in Journal
Steganalysis of Neural Networks Based on Symmetric Histogram Distribution
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Review and Comparative Study of Differential Evolution Algorithms in Solving Inverse Kinematics of Mobile Manipulator

1
School of Mechanical Engineering, Beijing Institute of Technology, Beijing 100081, China
2
School of Mechatronical Engineering, Beijing Institute of Technology, Beijing 100081, China
*
Author to whom correspondence should be addressed.
Symmetry 2023, 15(5), 1080; https://doi.org/10.3390/sym15051080
Submission received: 10 March 2023 / Revised: 9 May 2023 / Accepted: 10 May 2023 / Published: 13 May 2023

Abstract

:
Mobile manipulator robots have become important pieces of equipment due to the high mobility of mobile subsystems and the high flexibility of manipulator subsystems. Considering the increasing degrees of freedom and the need to avoid singular locations, one of the most challenging problems is solving the inverse kinematics problem of mobile manipulator robots (IKMM). Of all the popular optimization algorithms, the differential evolution (DE) algorithm is the most effective method for quickly solving the IKMM problem with sufficient solutions. Currently, many strategies have been proposed for DE algorithms to improve the performance of solving mathematical problems; some symmetry strategies or symmetry functions have been introduced to DE algorithms. However, the effects of various DE algorithms on solving the actual IKMM lack a comprehensive explanation. Therefore, we divide various DE algorithms into three categories considering the control parameter selection and compare the specific optimization of various DE algorithms. Then, we compare the performance of various DE algorithms when solving the inverse kinematics problems of mobile manipulators with different degrees of freedom. Considering the effectiveness and the speed of the DE algorithm on the IKMM problem, we determine the best DE algorithm by comparing the error and time required to reach 100 random mission points and tracking the typical trajectories. Finally, the best-performing DE method is further improved by studying the selection of fundamental parameters in the best DE algorithm. Valuable conclusions are obtained from these experimental simulations, which can help with choosing an algorithm that is suitable for solving the inverse kinematics problem of mobile manipulator robots in practice.

1. Introduction

A mobile manipulator fixes a manipulator on a mobile platform to improve the performance of traditional fixed manipulator robots [1]. Mobile platform subsystems can increase the robot workspace and increase the flexibility of system operation [2]. Based on these advantages, mobile manipulator robots currently have become a topic of research and application in many fields, including outer space detection [3], object handling [4], environment detection [5], and personnel assistance [6,7]. In these studies of manipulator robots, forward kinematics have mainly been used to solve the position and posture of the robot end-effector [8]. The aim of inverse kinematics (IK) is primarily to find the angle of each driving joint for ensuring that the end effector can reach a point with a given position and posture [9]. Compared with the single result of forward kinematics, a mobile manipulator’s inverse kinematics are more complicated due to the nonlinear mapping of joint angles and end points [10]. At present, a mobile manipulator robot’s IK problem is more challenging than that of other fixed manipulator robots considering the limitations in practical applications, such as the increased complexity [11], stringent precision requirements [12], joint angles [13], and optimization of motion time [14].
To solve these challenging problem, researchers have proposed many methods, including the analytical method [15], Jacobian-based method [16], neural network method [17,18,19], numerical method [20,21], and swarm intelligence algorithm [22,23]. The analytical method [24] directly uses math formulas to describe the relationship between the end point and the driving joints based on the basic structure of the robot. Due to the increased complexity regarding degrees of freedom and structure, the geometric analysis method may be inappropriate for robots with high DOFs (Degree of freedoms). As one of the most traditional methods, the Jacobian-based method [25,26] is based on the continuous iteration of the Jacobian matrix in the speed layer to solve the IK problem. However, this method cannot effectively solve a singular value or reduce the solution time. By constructing multilayer neural learning, the neural network method [27,28,29] directly solves the nonlinear relationship between the joint angles and the end point. This method has higher complexity in programming and needs a longer time for high-degree-of-freedom robots. The numerical method [30] transforms the IK problem into quadratic programming by considering various constraints. Then, we finally obtain the final inverse kinematics result through various numerical solution methods [31]. In numerical methods, the inverse kinematics solution mainly focuses on the velocity and acceleration layers [32]. The position layer inverse kinematics cannot be solved, and accurate solution results cannot be obtained for various constraints and singular points. The swarm intelligence algorithm is still the most productive solution based on the characteristics of biological swarms. Various swarm intelligence methods [33,34] have been proposed, such as PSO (Particle Swarm Optimization), GA (Genetic Algorithm), AA (Ant Algorithm), and DE (Differential Evolution). The swarm intelligence algorithms have become the most effective method to solve the IK problem.
In all types of typical intelligent algorithms, the DE algorithm is the most effective and extensive, being widely used in solving TSP, path planning, trajectory tracking, etc. When solving the TSP problem, the path between nodes i and j is usually symmetrical, that is, the distance from node i to j is equal. Based on this characteristic, the DE algorithm can find the shortest distance that traverses all nodes with its explore and explosive ability. A multiobjective algorithm that hybridizes the DE algorithm with a PSO is proposed [35]. The path length, degree of safety, and degree of smoothness are taken as the the objectives to optimize. The experiment results reveal that the hybrid algorithm outperforms the other algorithms on three metrics. Researchers [36] proposed an ϵ -constrained adaptive DE algorithm to solve optimal power flow problems. The ϵ -constrained strategy is improved to tackle the constraints, and a p-best selection method based on the constraint violation is implemented in the adaptive differential evolution. Authors [37] propose a modified differential evolution algorithm (ENMDE, Efficient and New Modified Differential Evolution) to solve two short-term hydrothermal scheduling problems. In the improved algorithm, a self-tuned mutation strategy and a leading group selection strategy are used to select the local search method or the global search method based on the evaluation of the solution. The improved DE algorithm perform better than the conventional DE not only in providing the optimal solutions but also in reducing the computation. Authors [38] propose a new differential evolution variant (PDcDE, Population Diversity-controlled Differential Evolution) to estimate the parameters of solar PV models. In the improved algorithm, three strategies are introduced, the swarm size is adjusted by an auto-controlled population strategy, the scale factor is set by a diversity-controlled method, and a backward search is used to avoid the local optima. The results show that the performance of PDcDE is superior in efficiency and effectiveness for parameter estimation. The DE algorithm is also widely used for solving the IK problem. For example, the DE algorithm is applied to solve the IK problem of a fixed manipulator, showing that the performance of the DE algorithm with the rand1 method is better than the PSO algorithm through many experiments [39]. The author [40] propose an ISAMDE (Improved Self-Adaptive Mutation Differential Evolution.) algorithm and apply the DE algorithm to a mobile manipulator robot and compare the performance when tracking different trajectories, which show that the DE algorithm has many advantages in solving the IK of mobile manipulatosr. Compared with the traditional method, the DE algorithm [41] is applied to the collaborative task of multimobile manipulator robots. The method could effectively solve the problem by redefining the constraint conditions. Researchers [42] plan a minimum-acceleration trajectory for a humanoid robot. The results indicate that the improved DE algorithm is effective for this task with a seven-DOF manipulator. The DE algorithm [43] provides the fastest solution speed and the best solution, avoids singular points, and ensures smooth motion.
In the literature, researchers have continued to optimize the DE algorithm and have proposed various methods including FADE (Fuzzy Adaptive Differential Evolution) [44], SADE (Self-adaptive Differential Evolution) [45,46,47], JDE [48], JADE [49,50], CODE (composite Differential Evoluton) [51], SAMDE (Self-adaptive Mutation Differential Evoluton) [52], and ODE (Opposition-based Differential Evolution) [53,54,55]. These improvements have mainly focused on crossover operations, mutation operations, mutation factors, and crossover probability. Many symmetry strategies have been used in the improved algorithms; for example, the ODE algorithm uses the symmetry idea to generate a new opposite solution and ensure the diversity of the group. Additionally, common symmetric distribution functions such as the Cauchy distribution and Gaussian normal distribution have been introduced into NSDE (Neighbour Search Differential Evolution) and JADE. Various aspects have been reviewed and improved by researchers for solving mathematical problems. However, the DE algorithm lacks more in-depth analysis and research in solving the IK problem of mobile manipulators. For example, different DE algorithms perform differently when solving the IK problem. We need to determine how to optimize the performance of the DE algorithm for solving the inverse kinematics problem, which is the most appropriate DE algorithm for solving the inverse kinematics problem of mobile manipulators with different degrees of freedom, and how to set the control parameters in the most appropriate DE algorithm.
In this study, we mainly focused on the practical applications of the DE algorithm in solving the IK problem of mobile manipulators with various DOFs. The specific contributions can be summarized as follows:
(1)
We provide a detailed description of the improvement directions of typical differential evolution algorithms. To facilitate in-depth understanding and research, we effectively divide the various differential algorithms into three categories according to the selection of different control parameters.
(2)
We redefine the IK problem of mobile manipulators as a global optimization problem and propose a variety of different fitness functions to meet the constraints existing for the solution of robot IK problems. The specific steps of the differential evolution algorithm to solve the inverse kinematics problems are described.
(3)
We determine the most appropriate DE algorithm to obtain the solution for a mobile manipulator and to further improve the performance of the differential evolution algorithm through the selection and optimization of control parameters.
(4)
The influence of DOFs on the performance of different DE algorithms are also analysed. With the increasement of robot DOFs, the inverse kinematics problems become more complex, the difference in effectiveness and applicability of each algorithm become obvious. The comparison simulation experiments can help scholars optimize their improved DE algorithm and select proper parameter value and strategies effectively.
(5)
Specific optimization content of different DE algorithms is compared. The combination direction to hybridize the DE algorithm with other algorithms is also provided.
The rest of this paper is organized as follows: In Section 2, we establish a model of a mobile manipulator, and we specifically describe the problems of forward and inverse kinematics. In Section 3, we classify various differential evolution methods based on the key parameter selection methods and describe the improvement directions. In Section 4, we redefine the inverse kinematics of the mobile manipulator as a numerical optimization problem, and we describe the specific steps of the DE algorithm to solve the optimization problem. Section 5 describes multiple experiments that are designed to analyze the effects of various differential evolution methods on the inverse kinematics of different mobile manipulators and to determine the specific effects of parameters on the optimal differential evolution. The final section summarizes the paper.

2. Preliminary Knowledge

In this section, we introduce the basic structure and key technologies of mobile manipulator in forward kinematics and inverse kinematics.

2.1. Physical Model

To reduce the difficulty of the calculation, researchers have treated the mobile manipulator as an open-loop chain structure by referring to manipulator modeling technology. As such, the forward kinematics of a mobile manipulator (FKMM) can be established by analyzing the motion relationship between the driving joints and connecting links. Although the structure and DOFs of a mobile manipulator may widely differ the basic kinematics modeling method is the same. Figure 1 depicts a typical simplified structure of a mobile manipulator robot.

2.2. Kinematics Model

The transformation matrix method is widely used for solving the forward kinematics of mobile manipulators. Therefore, except for the corresponding joint angles, the end position of the mobile manipulator is affected by the fixed position of the manipulator subsystem and the current state of the mobile platform subsystem. The assumption is that the mobile manipulator robot moves on the horizontal plane ( X O Y ) . Then, the end position of the manipulator is controlled by the corresponding joint angle. Therefore, the control variable of the robot is expressed as follows:
q = [ q m , q a ] T = [ d x , d y , q z , q 1 , q 2 , q 3 , , q n ] T
where q m represents the control variable of the mobile platform subsystem, q a represents the control variable of the manipulator subsystem, d x represents the movement distance along the X axis of the mobile platform, d y represents the movement distance along the Y axis of the mobile platform, q z represents the rotation angle around the Z axis of the mobile platform, and q i represents the drive joint of the robotic arm.
To reduce the difficulty of kinematic modeling, we directly establish a standard coordinate frame on the mobile platform instead of the three coordinate frames established by other researchers. Additionally, the joint-fixed coordinate frame is directly established based on the typical SDH (standard Denavit-Hartenberg) method. Considering the fixed connection between the two subsystems, the position and posture of the mobile manipulator’s end effector can be directly expressed as follows:
T e = o T c c T b b T e
where o T c , b T e , and c T b represent the homogeneous transformation matrix of the mobile, tool-fixed, and based-fixed coordinate frames, respectively.
In the actual solution process, the generally specified task only contains the position of the target point in Cartesian space (not including the pose). Therefore, we need to extract the corresponding position from the homogeneous transformation matrix, which can be expressed as:
p = f ( q )
where, p represents the position of the end effector, q indicates the corresponding driving joints, and f ( ) represents the extracted function from the forward kinematics matrix of the mobile manipulator. And the IK problem of the mobile robot can be directly expressed as:
q = f 1 ( p )
where f 1 ( ) represents the IK function of the mobile manipulator, q represents the final joint angle, and p represents the position information (or including posture information) of the end effector.
Most mobile manipulators have redundant degrees of freedom and variable structural features. Therefore, theoretical analysis methods cannot effectively be applied on the robot. The conventional solution method is the pseudo-inverse method in the speed layer. However, the method has many shortcomings such as not avoiding the singular position, higher complexity in solving the matrix inverse, and large error in the final result. Therefore, researchers have used various popular optimization algorithms to solve the IK problem. Among these methods, the DE algorithm performs well so has become the most effective solution method.
Remark 1.
Positioning of the mobile platform. To ensure precision and stability, the mobile platform is mainly composed of rigid components, and the connecting parts are rigidly connected. The movement process does not occur skidding or sliding. The angular velocity of the driving wheels of the mobile platform is directly controlled by motors. The formulation of the mobile-fixed coordinate frame is expressed as follows:
o T c = [ cos ( q z c ) sin ( q z c ) 0 p x c sin ( q z c ) cos ( q z c ) 0 p y c 0 0 1 p z c 0 0 0 1 ]
where p x c , p y c , p z c represents the center position information of the drive wheels, and q z c represents the posture information.
Remark 2.
Positioning of end effector. Because the joint-fixed coordinate frame is established on each joint based on the traditional modeling method, the homogeneous transformation matrix can directly describe the position and posture of adjacent coordinate frames. Therefore, the position and posture of the end effector can be expressed as follows:
b T e = b T 1 · 1 T 2 · · n 1 T n · n T e
where n 1 T n represents the homogeneous transformation from the joint(n−1)-fixed coordinate frame to the joint(n)-fixed coordinate frame. The formulation can be expressed as:
i 1 T i = R o t ( q i ) · T r a n ( d i ) · R o t ( α i ) · T r a n ( a i )
where α i represents the twist angle of the links, a i represents the link length, q i is the rotation joint angle, d i represents the link offset.
Remark 3.
Positioning of the connection components. The position of the connection part is determined in the actual application of the robot. Therefore, we can determine the relationship between the based-fixed coordinate frame and the mobile-fixed coordinate frame:
c T b = T l ( [ d x c b d y c b d z c b ] ) R x ( q x c b ) R y ( q y c b ) R z ( q z c b )
where d x c b , d y c b , and d z c b represent the three distances that the based-fixed coordinate frame moves along the three axes of the mobile-fixed coordinate frame; q x c b , q y c b , and q z c b represent the three rotation angles of the based-fixed coordinate frame around the three axes of the mobile-fixed coordinate frame; T l ( ) represents the homogeneous transformation matrix; and R x ( q x c b ) , R y ( q y c b ) , R z ( q z c b ) represents the homogeneous transformation matrix of the rotation motion along the X , Y , Z axes, respectively.
Remark 4.
Target point task. Due to the mobile manipulator being far from the target point in the early stage of the actual task, the inverse kinematics solution only ensures that the all positions can be accurately reached by the end effector. When reaching the position near the target point, the robot needs to accurately perform the task, and the state of the target task needs to be considered.

3. Typical DE Algorithms

In this section, we describe the specific steps of the DE algorithm. To facilitate further research on DE algorithms, we classified the various DE algorithms based on the coefficient of the mutation operation. Additionally, we compared and summarized the exact differences and characteristics of various DE algorithms.

3.1. Basic DE Algorithm

The DE algorithm is one of the simplest methods of the swarm intelligence algorithm. The solution of the optimization problem based on the DE algorithm is obtained through a cooperation and competition strategy between different populations in a group. The implementation of the differential evolution algorithm requires the following four steps: initialization, mutation, crossover, and selection.
(1)
Initialization. Various sets with NP elements are randomly constructed to solve the optimization problem. To ensure that each element in the created sets meets the lower and upper boundaries, we use the Monte Carlo method to initialize the individuals. Each individual can be expressed as follows:
x i , g o j = x min j + r a n d ( 0 , 1 ) ( x max j x min j ) , j = 1 , 2 , , N P
where x i , g o j represents the j t h element in the i t h set in the group; x m i n j and x m a x j represent the lower and upper boundary, respectively; and r a n d ( ) represents a random number in [ 0 , 1 ] .
(2)
Mutation. New individuals are constructed by multiple different individuals in the parent group. A mutation strategy is used to distinguish it from other intelligence algorithms. This step can be explicitly expressed as:
V i , g = X r 1 , g + F · ( X r 2 , g X r 3 , g )
where V i , g represents the new individuals different from the parent group; X r 1 , g , X r 2 , g , and X r 3 , g represent three different sets in the parent group; F represents the scaling factor; and ( X r 2 , g X r 3 , g ) represents the difference vector used for mutation.
(3)
Crossover. A new group is established through crossover operations between parent and mutant individuals. To ensure the group’s evolution, we combine parental and variant individuals to create a new group during the crossover process. The crossover probability of mutation is determined, which can be expressed as:
u i , g j = { v i , g j , i f ( r a n d ( ) < C R ) o r ( j = j r a n d ) x i , g j , e l s e
where u i , g j represents the new individual established by the crossover process, v i , g j represents the new individual generated by the mutation, x i , g j represents the original individual in the parent group, and C R represents the cross-ratio coefficient.
(4)
Selection. The best set is selected by comparing the fitness function in a different set of the new group. In this step, the current optimal set is selected from these above-mentioned overall cross-mutated group, which can be expressed as:
x i , g + 1 j = { u i , g j , i f ( f i t ( u i , g j ) < f i t ( x i , g j ) ) x i , g j e l s e
where x i , g + 1 j represents the best individual of the current group, and f i t ( ) represents the fitness function of the objective problem.

3.2. Optimized DE Algorithm

As a mutation algorithm of the genetic algorithm, the DE algorithm has become popular in research due to having fewer control parameters and higher solving efficiency. According to the critical operation steps, the optimization of the DE algorithm has mainly focused on the crossover and mutation processes. According to the different settings of the control parameters, we divided various DE algorithms into three categories and studied the specific optimization trend of DE algorithms.

3.2.1. Deterministic Parameter Control

Deterministic parameter control means that the scaling factor F and the crossover probability CR take fixed values and do not change over time. This type of DE algorithm is relatively simple, and the most typical optimization methods include the typical DE algorithm (TDE), the opposition-based learning DE algorithm (ODE), the composite DE algorithm (CODE), and the adaptive mutation DE algorithm (AMDE).
(A1) TDE
The aim of the typical DE is to obtain a more optimized group through the correction of individual information in the group. As an essential step of the DE algorithm, the scaling factor and the difference vector of the mutation can substantially impact the solution speed and accuracy of the population. The mutation process also has a key control variable that affects the diversity of the population. Therefore, many researchers choose mutation operation as the primary trend for improving the DE algorithm. According to the initial population, the mutant individual can choose the best individual or a random individual in the current group as the primary solution. The difference vector can be solved by randomly selecting different sets in the group or selecting the best set and some random sets. Through the selection of two different parameters, researchers have developed various DE algorithms. DE represents the differential evolution principle of the system; best or rand represents the random selection and the latest selection method; and 1 or 2 represents the number of the different vector used in the system. The current mainstream mutation operations of the DE algorithm are as follows:
( 1 ) D E / r a n d / 1 :    V i ( t + 1 ) = X r 1 ( t ) + F ( X r 2 ( t ) X r 3 ( t ) ) ( 2 ) D E / b e s t / 1 :    V i ( t + 1 ) = X b e s t ( t ) + F ( X r 1 ( t ) X r 2 ( t ) ) ( 3 ) D E / r a n d / 2 :    V i ( t + 1 ) = X r 1 ( t ) + F ( X r 2 ( t ) X r 3 ( t ) + λ ( X r 4 ( t ) X r 5 ( t ) ) ( 4 ) D E / b e s t / 2 :    V i ( t + 1 ) = X b e s t ( t ) + F ( X r 1 ( t ) X r 2 ( t ) ) + λ ( X r 3 ( t ) X r 4 ( t ) ) ( 5 ) D E / c u r r e n t b e s t / 1 :    V i ( t + 1 ) = X i ( t ) + F ( X b e s t ( t ) X i ( t ) ) + λ ( X r 1 ( t ) X r 2 ( t ) )
where r 1 , r 2 , and r 3 represent the three random indices of the fitness functions in the current group, respectively; and b e s t represents the index of best fitness function in current group.
The result of the mutation cannot guarantee that the new set is within the constraints of the optimization problem. Therefore, researchers again restrict the individuals to ensure that the crossover results are within the specified constraints. The specific solution results are:
{ u i = v i , i f ( u L < v i < u U ) u i = u L + r a n d · ( u U u L ) , o t h e r w i s e
where u i represents the mutated individual, [ u L , u U ] represents the constraint range of the group in the solution process, and v i represents the latest mutated individual.
(A2) ODE
The ODE algorithm [53] mainly optimizes the DE algorithm by selecting the initial population. The basic principle of the initial population is based on opposition-based learning. This method mainly adds the inverse function of random data, and a new symmetry solution is generated based on the initial solution, ensuring that the initial population is more evenly distributed. The inverse function of a random number in a given range can be expressed as:
X * ( i ) = X l ( i ) + X u ( i ) X ( i )
where X * indicates the inverse function; X u and X l indicate the maximum and minimum values in the given range, respectively; and X indicates the random number.
After solving the corresponding fitness and effective sorting, a more suitable individual is selected to meet the required population size from the initial population in the ODE algorithm. Assuming PB is denoted as the randomly selected population, PO is denoted as the inverse function of the corresponding population, and the overall population can be expressed as P = PB + PO. After the crossover operation, the population is optimized again according to the random number and the inverse function learning probability. According to the mutation operation, a “neighbor-neighbor” strategy is redefined, which is explicitly expressed as:
V r 3 ( t + 1 ) = X i ( t ) + F ( X b e s t ( t ) X r 3 ( t ) ) + λ ( X r 1 ( t ) X r 2 ( t ) )
where i and r 3 are selected from the best-ranked populations, which are mainly used for the optimal detection of adjacent space; and r 1 and r 2 are randomly selected from the original population, which are used to improve the detection capability of the global scope.
(A3) CODE
The composite DE algorithm is developed by improving the mutation operation and control parameters. In most situations, different mutation operations have different effects on the results. So, multiple mutation operations and control coefficients are selected for the DE algorithm based on the above considerations.
The CODE algorithm randomly selects three mutations from various mutation strategies as the next generation. After each population is initialized, three different new populations are generated based on the three mutation strategies. The specific mutation operations and the coefficients can be expressed as:
( 1 ) D E / r a n d / 1 : [ F = 1.0 , C r = 0.1 ]      V i ( t + 1 ) = X r 1 ( t ) + F ( X r 2 ( t ) X r 3 ( t ) ) ( 2 ) D E / r a n d / 2 : [ F = 1.0 , C r = 0.9 ]      V i ( t + 1 ) = X r 1 ( t ) + F ( X r 2 ( t ) X r 3 ( t ) + λ ( X r 4 ( t ) X r 5 ( t ) ) ( 3 ) D E / c u r r e n t t o r a n d / 1 : [ F = 1.0 , C r = 0.2 ]      V i ( t + 1 ) = X i ( t ) + F ( X r 1 ( t ) X i ( t ) ) + λ ( X r 2 ( t ) X r 3 ( t ) )
where r 1 , r 2 , r 3 , and r 4 are randomly selected from the group; i indicates the original population; and V i represents the result of the mutation operation.
The CODE algorithm has many mutation strategies, but the control parameter is still a fixed value. Therefore, the CODE algorithm can be regarded as an optimization algorithm with a fixed coefficient of determination.
(A4) AMDE
The AMDE algorithm also selects different mutation operations to increase the group’s diversity. Researchers combined rand and best mutation to maintain the local convergence performance and global exploration ability. When the new set is superior to the current individual, the parent individual is directly replaced to produce the next individual. The AMDE algorithm chooses the traditional rand/1 and best/2 as the basic mutation operations. rand/1 can maintain the global exploration ability of the system, and best/2 is used to maintain the convergence performance. To effectively select two parameters in the mutation process, any specific selection is based on comparing the total time of the population iteration process and the random number. The corresponding differential evolution method can be described as:
V i ( t + 1 ) = { X r 1 ( t ) + F ( X r 2 ( t ) X r 3 ( t ) ) ; i f ( r a n d < 1 ( t / T ) 2 ) X b e s t ( t ) + F ( X r 1 ( t ) X r 2 ( t ) ) ; o t h e r w i s e
where r 1 , r 2 , and r 3 are randomly selected from the original population; T represent the maximum iteration number of the problem.
Constraints are applied to the new individuals in the traditional algorithm to ensure that the population individuals are within a given range space to ensure that the system’s mutant individuals are within a given motion solution range; specifically, this can be expressed as:
W i ( t + 1 ) = { X l r a n d · ( X l X u ) ; o t h e r w i s e V i ( t + 1 ) ; i f ( X l < V i < X u )
where X l represents the maximum value and the latest value of the given population for the individual, r a n d represents the random value in the range [ 0 , 1 ] , V i represents the current iteration individual, and W i represents the new individual selected.
Generally speaking the performance of an algorithm is influenced by its explore ability and exploit ability, the random (rand) strategy can enhance the explore ability, help the group keep diversity, and prevent the group from falling into local optimum, the best strategy can improve the exploit ability of the algorithm and emphasize the rate of convergence. Compared with the DE/best/1, DE/best/2 and DE/current-best/1 algorithms, the fitness values of the DE/rand/1, DE/rand/2, ODE, and CODE algorithms converge to a small range. Due to the random strategy and the opposite strategy in the algorithms. The group shows better diversity, so their results are relatively stable. However, the precision of the algorithms may sometimes be low for the lack of local search. The performance of DE/best/1 and DE/best/2 are strongly affected by the scale factor F. Although the fitness values of the DE/best/1, DE/best/2, DE/current-best/1 and CODE algorithms converge to a large range, some of their results are highly precise for the best strategy; they can solve high-precision problems that other algorithms cannot with better exploit ability. Due to many strategies are used in the CODE algorithm, the calculation time is always long.

3.2.2. Adaptive Parameter Control

In adaptive parameter control methods, the coefficient of variation F and the crossover probability CR are randomly selected. However, the choice of the two key parameters may or may not be affected by the previous results. The most typically used adjustment coefficient optimization method is the DE algorithm with neighborhood search (NSDE).
(B1) NSDE
The basis of the NSDE algorithm is that different mutations perform differently in the solving areas near the optimal local value. A smaller mutation factor can ensure convergence near the optimal local value, but it cannot obtain the global optimal solution. A larger mutation factor can improve the searchability of the nearby global optimal solution, but more time is required to achieve local convergence. Therefore, researchers proposed a random variable factor to optimize the problem.
In the NSDE algorithm, d = x r 1 x r 2 is the step size in the adjacent space exploration. When near the optimal value, the value is automatically reduced. When the crosser coefficient F adopts a changing value, more jump steps can be generated. Compared with the fixed mutation parameters, this method can generate a more diverse group. At the same time, a variable mutation factor can ensure that the solution result escapes from the local range to reach the optimal global range. Because Gaussian random distribution provides better mean concentration performance and the Cauchy random distribution has better global distribution performance, researchers have effectively used the above methods to improve the DE algorithm. The specific variation factor can be expressed as:
F = { N i ( 0.5 , 0.5 ) ; i f ( U ( 0 , 1 ) < f p ) δ ; o t h e r w i s e
where N i ( 0.5 , 0.5 ) represents a random number in the Gaussian distribution with a corresponding mean of 0.5 and a standard deviation of 0.5; δ represents a random number in the Cauchy random distribution with the corresponding key parameter t = 1 .
The NSDE algorithm improves the neighborhood search mechanism and make better use of local information in search space. So it shows a high optimization success rate and the precision is relatively high; however, the neighborhood search mechanism may increase the computational complexity of the algorithm. the calculation of the algorithm is large and the time-consuming. The performance of the algorithm is highly dependent on the characteristics of the problem and may not be the optimal choice for some problems.

3.2.3. Self-Adaptive Parameter Control

We obtain the critical parameters by applying the concept of “evolution in evolution” in self-adaptive parameter control optimization methods. Therefore, some researchers have added self-adjustment functions to the coefficient of variation F and crossover probability CR of the DE algorithm. The most typical adaptive adjustment coefficient optimization methods include JDE, JADE, and SADE.
(C1) JDE
The mutation and crosser operations strongly affect the DE algorithm when solving optimization problems. The values of the different coefficients affect a DE algorithm having the same mutation operation. To solve all kinds of problems with the global best solution, researchers proposed a new method by using additional variables to control the crosser and variation factors. This method can ensure that the two key parameters jump within a specified range and that the best variation parameters can be obtained in the next solution.
In the JDE algorithm, the crossover factor is between the maximum and minimum values in the population, which is determined by a random control variable τ 1 . The factor CR is directly determined by random numbers, which can be affected by the control variables τ 2 . These key parameters are expressed as follows:
F i , G + 1 = { F l + r a n d 1 F u ; i f ( r a n d 2 < τ 1 ) F i , G ; o t h e r w i s e ; C R i , G + 1 = { r a n d 3 ; i f ( r a n d 4 < τ 2 ) C R i , G ; o t h e r w i s e
where F represents the maximum and minimum values; τ 1 and τ 2 represent the possible adjustment functions of the mutation and the crossover factors, respectively; r a n d 1 , r a n d 2 , r a n d 3 , and r a n d 4 are three different random numbers between [ 0 , 1 ] . We can control the corresponding variation and crossover factors by adopting adaptive adjustment.
(C2) JADE
The JADE algorithm is a new type of differential evolution algorithm proposed by scholars [49]. In the DE algorithm, mutations best/1 and best/2 may cause premature convergence because the best method mainly explores the local optimum value field space.
In the algorithm, a global population is generated by superimposing the current population on the parent population. Hypothesis: The mutated individual of the population is expressed as A, the current population is expressed as P, and the overall population is expressed as ( P + A ) . However, we must avoid exceeding the given population number caused by continuously increasing the number of populations. Therefore, once the overall population is achieved, we must randomly remove a population from ( P + A ) . The corresponding mutation operation can be expressed as:
U i ( t + 1 ) = X i P ( t ) + F 1 ( X b e s t P ( t ) X i P ( t ) ) + F 2 ( X r 1 ( t ) X r 2 P A ( t ) )
where X b e s t p ( t ) , is randomly chosen as one of the top 100 p % individuals in the current population with p ( 0 , 1 ] , r 2 represents the random selection from the population ( P + A ) , and b e s t represents the best fitness index of the entire population.
In JADE algorithm, the symmetry function, random uniform distribution and Cauchy random distribution are introduced to keep the diversity of the group, the crossover probability CR is a random uniform distribution number (standard deviation is U C R , the average disturbance is 0.1), and the initial value of U C R is 0.5. Similarly, the variation factor F is generated by Cauchy random disturbance (local disturbance is UF and Range 0.1), and the initial value of U F is 0.5. Specifically, these key parameters can be expressed as follows:
{ C R i = r a n d n i ( u C R , 0.1 ) u C R = ( 1 c ) u C R + c · m e a n A ( S C R ) m e a n A = C R S C R S C R N ; { F i = r a n d c i ( u F , 0.1 ) u F = ( 1 c ) u F + c · m e a n L ( S F ) m e a n A = F S F F 2 F S F F
where r a n d n represents the random distribution number, r a n d c represents the Cauchy random distribution, m e a n A represents the average value, m e a n L represents the Lehmer mean, and S C R and S F represent the corresponding mutation factor and crossover probability when the final individual result is a new population individual, respectively.
(C3) SADE
The SADE (Self-adaptive Differential Evolution) algorithm effectively combines various mutation strategies to increase the diversity of the system. The next generation of mutated individuals is generating by selecting the best individual from various individuals generated from three different mutation operations. In multiple mutation strategies, the best method has a high convergence rate, but the phenomenon of falling into local optima may occur. Additionally, the rand method has strong global detection ability. Therefore, the random mutation operation is the most basic principle used to avoid the phenomenon. At the beginning, researchers used two basic mutation operations, rand/1 and best/1. With the rapid development of basic differential evolution algorithms, the basic mutation operations are transformed into four types.
( 1 ) D E / r a n d / 1 :      V i ( t + 1 ) = X r 1 ( t ) + F ( X r 2 ( t ) X r 3 ( t ) ) ( 2 ) D E / r a n d b e s t / 1 :      V i ( t + 1 ) = X i ( t ) + F ( X b e s t ( t ) X i ( t ) ) + F ( X r 1 ( t ) X r 2 ( t ) + X r 3 ( t ) X r 4 ( t ) ) ( 3 ) D E / r a n d / 2 :      V i ( t + 1 ) = X i ( t ) + F ( X r 1 ( t ) X i ( t ) ) + λ ( X r 2 ( t ) X r 3 ( t ) ) ( 4 ) D E / c u r r r e n t b e s t / 1 :      U i ( t + 1 ) = X i ( t ) + F ( X r 1 ( t ) X i ( t ) ) + λ ( X r 2 ( t ) X r 3 ( t ) )
The selection probability of each mutation operation can be specifically described as:
p k , G = S k , G k = 1 K S k , G S k , G = g = G L P G 1 n s k , g g = G L P G 1 n s k , g + g = G L P G 1 n f k , g + ζ , ( k = 1 , 2 , k )
where n s and n f represent the number of successes and failures, respectively.
Again, the key parameter used in the next step is determined based on the success probability of various mutation operations. Then, the mutation and crossover factors are further optimized based on the NSDE algorithm to determine the key parameters. The mutation factor F is randomly selected, and the crossover factor is further determined by the success efficiency of various mutation parameters, which can be expressed as:
F = N o r m r n d ( 0.5 , 0.3 ) ; R c = N o r m r n d ( C R m , 0.1 ) ;
where N o r m r n d represents the symmetry function is—random normal distribution.
(C4) ISAMDE
The ISAMDE algorithm combines the AMDE and adaptive scaling factor AF strategies. The AMDE strategy is same as that of the AMDE (A4) algorithm mentioned above. The AF strategy improves the performance of the DE algorithm by considering the current iteration number and error value: it can effectively balance the exploration and exploitation abilities of the algorithm. At the beginning of the iteration, the scaling factor is assigned a value of one, so the exploration ability is strong. The error value is affected by the current iteration number of the algorithm, which is less than the set value E 0 . The AF can be expressed as:
A F = { ϵ ( t ) 2 · 2 · 10 6 + 0.5 , ϵ < E 0 1 , o t h e r w i s e
where ϵ ( t ) represents the error, and the value of E 0 is related to the specific engineering problems.
(C5) ENMDE
The ENMDE algorithm combines the self-tuned mutation strategy with the leading group selection strategy. The self-tuned mutation strategy includes four typical DE algorithms: DE/rand/1, DE/best/1, DE/rand/2, and DE/best/2. The TDE algorithms can be divided into two groups: the rand group, which includes DE/rand/1 and DE/rand/2; and the best group, which includes DE/best/1 and DE/best/2. The rand and best groups are selected by comparing the fitness distance ratio with the average fitness distance ratio. They are expressed as follows:
Δ F T d = F T d F T b e s t F T b e s t
Δ F T m e a n = ( d = 1 N p F T d ) N p F T b e s t F T b e s t
where Δ F T m e a n represents the average fitness distance ratio; Δ F T d represents the fitness distance ratio; F T d represents the fitness function of the solution under consideration d; N p represents the population size; F T b e s t represents the fitness function of the best solution; F T m e a n represents the mean value of all individuals’ fitnesses. The process of self-tuned mutation is described in detail in the following table. After the group is selected, the final mutation strategy is selected by considering the mutation mode factor (MMF). The specific process is expressed as Table 1:
The leading group selection strategy is also used in this improved DE algorithm, where the individuals x = [ x 1 , x 2 , , x N P ] and u = [ u 1 , u 2 , , u N p ] are integrated into a new swarm, and then Np best solutions are selected and assigened to x, where u represents the individual are operated after crossover.
(C6) PDcDE
In the PDcDE algorithm, the swarm size is auto-controlled, the population is divided into two subpopulation– N 1 , N 2 , the best N 1 individuals are used to exploit new solution and the left N 2 individuals are used to explore new solution. The mutatant strategies are formulated as:
V 1 = X 1 s t r 1 + F 1 · ( X 1 s t r 2 ( t ) X 1 s t r 3 ( t ) )
V 2 = X 1 s t r 4 + F 2 · ( X r 5 ( t ) X r 6 ( t ) )
where 1 s t represents the individuals which are selected from the first group ( N 1 ). r 1 , r 2 , r 3 , r 4 , r 5 and r 6 are randomly generated different indices, r 1 , r 2 and r 3 are selected from the first subpopulation ( N 1 ), while r 4 , r 5 , r 6 are selected from the whole population. The swarm size N is dynamically changed by considering whether the current best solution is updated or not, if it updated, a parameter c is used to count by increasing one, when it reached a preset threshod value L, the worst individual will be removed until the swarm size reach the minimum size N m i n . If the current best solution is not updated, a parameter c + is also used to count by increasing one, when it reaches a preset threshod value L, a randomly individual is introduced into the swarm until the swarm size reaches the maximum size N m a x . The diversity-controlled paremeter setting is another strategy in the PDcDE algorithm, the scale F 1 and F 2 are for the N 1 subpopulation and N 2 subpopulation, respectively. They are dynamically generated by considering the population diversity. The diversity at the jth dimension is expressed as:
D i v j = 1 N i = 1 N ( | | X i j X j ¯ | | ) 2
X j ¯ = 1 N i = 1 N X i j
where D i v j represents the diversity of the swarm at the jth dimension. X i j represnts the jth element in the ith individual. X j ¯ represents the arithmetic mean of the swarm at jth dimension. The scale factors of F 1 j and F 2 j are expressed as:
F 1 j = D i v 1 j D i v 1 j + D i v 2 j
F 2 j = D i v 2 j D i v 1 j + D i v 2 j
where D i v 1 j and D i v 2 j represents the population diversity of the N 1 group and N 2 group, respectively.
The characteristic of diversity will lead the swarm search in different way, if the diversity is large, the swarm will search and explore in the large search space, conversely, if the diversity is small, the swarm will search and exploit in a small search space.
Finally, a backward search strategy is also proposed, it replaces the crossover solution if current best solution is not updated in successive L iteration, the formulations can be expressed as:
U i ( t ) = V i ( t ) + ( r a n d 0.5 ) · r
r = V i ( t ) X b e s t ( t )
where U i ( t ) is a trial solution, V i ( t ) representes the muatated solution in current generation, the rand is generated between 0 and 1.
The parameters F and CR which are needed to be set for variation and crossover in the JADE algorithm can be selected adaptively without artificial setting. The algorithm sometimes need enough iteration times and population size to obtain the optimal solution. It performs better in solving high-dimension problems but weak in dealing with low-dimension problems. JADE’s performance depends heavily on the setting of parameters, and different parameter settings may lead to different results. Due to the parameter F or CR are changed, the convergence accuracies of JDE, SADE, and PDcDE are high; however, the convergence rate sometimes are slow for the computational complexity. The stability of the PDcDE algorithm is high; however, the algorithm contains many redundant calculations. Because the rand strategy or best strategy of ENMDE are adaptive, the algorithm shows high precision. However, the calculation time sometimes maybe long for the complex judgment process. The influence of dynamically swarm size on the calculation results are uncertain. The ISAMDE usually shows better convergence rate and precision for taking advantage of the AMDE, however, sometimes the scale factor F and other parameters are difficult to set, the performance of the algorithm is largely depends on parameter settings, different parameter settings may lead to different results. So the scale factor and other parameters are always set based on experience.

3.3. Comparison of DE Algorithms

The above-mentioned DE algorithms mainly involve four basic parameters: the crosser coefficient, crosser operation, population size, and coefficient of variation. NP indicates the number of collective individuals in the population, which is generally selected by the user. If the NP is larger, the diversity of the population increases, and the optimal solution is more likely to be obtained. However, the longer the calculated time, the lower the system’s convergence performance. If NP is too small, the diversity is lost, and the algorithm falls into a local optimal solution. The size of NP is generally selected as 5 to 10 times the individual dimension and cannot be less than 4; otherwise, the mutation operation cannot be completed. The larger the value of the variation factor F, the larger the disturbance amplitude of the differential vector, the lower the population diversity, and the local minimum is arbitrarily found. When F is larger, the disturbance of the two sets is larger, and the rapid convergence of the system cannot be guaranteed. F is generally selected according to experience, ranging in value between 0 and 1, with a general value is 0.5. CR represents the proportion of mutated individuals. When CR is small, fewer individuals are mutated. The parent individuals can be maintained to ensure a slower convergence rate. When CR is larger, the proportion of the number of mutation sets is larger, which can improve the system’s local exploration and acceleration convergence. The value of CR ranges between 0 and 1. To fully understand the improvements of various algorithms, we compared the improvements of various differential evolution algorithms, and the results are shown in Table 2.

4. Solving Inverse Kinematics with DE Algorithm

To obtain the IK solution, in this section, we redefine the fitness parameters according to the specific requirements of the task and summarize the specific process and basic steps of the DE algorithm.

4.1. Redefine Inverse Kinematics of Mobile Manipulator

To move a mobile manipulator’s end to a target task point X t , the corresponding angle needs to be obtained by solving the IK solution of the robot. However, due to the extreme redundancy and high DOFs of the manipulator, most traditional solution strategies for fixed manipulator can no longer be effectively applied to mobile manipulator robots. We assume that the position and posture information of the given task at the end is:
T d = [ R , P ; 0 , 1 ] T
where R represents the end posture of the robot, and P = [ P x , P y , P z ] T represents the end position.
The corresponding driving joint angle solved by the inverse kinematics of the mobile manipulator can be expressed as q = ( d x , d y , q z , q 1 , q 2 , , q n ) . When the robot moves to the joint angle, the error between the end of the mobile manipulator and the desired specified point can be expressed as:
E r r o r = T d T e ( q ) = [ O e r , P e r ; 0 1 3 , 1 ]
where T e represents the forward kinematics of the robot, O e r represents the posture error, and P e r represents the position error.
For the same specified position and posture, many different combinations of joint angles can be used to control the mobile manipulator to move to the specified point. Therefore, these joint angles can be directly defined as a solution set, which is expressed as follows:
C s = [ d x 1 d y 1 q z 1 q 1 1 q 2 1 q n 1 d x 2 d y 2 q z 2 q 1 2 q 2 2 q n 2 d x j d y j q z j q 1 j q 2 j q n j ]
where C s represents the overall set of solution results, and j represents the number of iteration times.
When the given task is at a specified position, the inverse kinematics solution can be directly defined as an error function. Therefore, the IK problem of the robot can be re-expressed as finding the combination of drive joint angles within the limited range to make the function reach the minimum value, namely:
s u b : f ( q ) = min T d T e ( q ) = 0
where f ( ) indicates the fitness function of a given mobile robotic arm, T d indicates the position and posture of a given task, and T e represents the actual position and posture.
Remark 5.
When the end position is individually given, and the state is not restricted, the IK can be expressed as:
t a r : f 1 ( q ) = min P d P e ( q ) s u b : q i L < q i < q i U ;
where f 1 ( ) represents the fitness function, P d represents the desired position, P e represents the actual end position, and q i L , q i U indicates the maximum and minimum driving joint positions.
Remark 6.
When the position and posture of the end of the mobile manipulator are all in a given state, the inverse kinematics problem can be expressed:
t a r : f 2 ( q ) = min ( P d P e ( q ) + R d R e ( q ) ) s u b : q i L < q i < q i U ;
where f 2 ( ) represents another fitness function, R d R e ( q ) represents the posture error value of the mobile manipulator’s end, and P d P e ( q ) represents the position error value.
Remark 7.
During actual movement, we need to choose a set of results as the best solution. To move to the specified position smoothly, the result with the smallest angle of change must be selected as the control of the robot’s motion. The problem can be directly defined as a selection function; specifically, it can be expressed as the smallest result in the current joint and the solution group. Therefore, we define the objective function as the function with the smallest joint angle and the smallest expected position error as:
t a r : f 3 ( q ) = min ( w 1 ( P d P e ( q ) 2 + R d R e ( q ) 2 ) + w 2 p n p o 2 ) s u b : q i L < q i < q i U ;
where f 3 ( ) indicates the other fitness function, p n indicates the driving joint angle obtained at the current time, and p o indicates the driving joint angle obtained at the previous time.

4.2. De Algorithm Code for Solving Inverse Kinematics

Different DE algorithms can be used to solve the IK problem. Although the key technologies of various DE algorithms are different, the basic process of solving inverse kinematics with these DE algorithms does not substantially differ and can be described as follows:
Step 1: Obtain the basic parameters of the mobile manipulator and set the target point of the robot.
Step 2: Initialize the basic parameters, which include population NP, number of iterations N, crossover factor CR, mutation probability F, and number of driving joints D.
Step 3: Initialize the population and calculate the fitness value of each individual in the group.
Step 4: Select the population according to the mutation operation to perform the mutation operation, and update the range of the new population.
Step 5: Generate new population individuals according to the crossover principle to complete the basic population evolution.
Step 6: Calculate the fitness function of the new individual and determine whether the population meets the conditions. If not, return to Step 4 to update the population again. If so, proceed to Step 7.
Step 7: Save the drive joint data and complete the joint solution. The flowchart of the DE algorithm used in solving the inverse kinematics is shown as Figure 2

5. Experimental Simulation

To compare the performance of the various differential evolution methods in solving mobile manipulator problems, we choose three typical mobile manipulator robots as the experimental objects, and we use random point tasks and continuous trajectory tasks. In the random point task, we set the position and posture of each random point to compare the various DE algorithms. For the continuous trajectory tasks, we separately set the position of each random point only to test the performance of the various DE algorithms. In addition, the control parameters are set on the best differential evolution method. To facilitate practical applications, the computer parameters used in this study are an Intel(R) Core(TM) i5-7500 CPU @3.4HZ, RAM @8G. Additionally, we calculate the statistics on the success rate and solution time of the various algorithms for solving inverse kinematics.

5.1. Equipment Description

Various DE algorithms are examined using three typical mobile manipulators with different DOFs. The control variable of the mobile-fixed coordinate frame can be expressed as q m = [ d x , d y , q z ] T , where q m represents the three virtual joints of the mobile robot, d x and d y are the translation joints, and q z is the rotation joint. The manipulator uses the typical manipulator robots as actuators, including KUKA5, UR5, and Robot7 as Figure 3; the corresponding joint control variables are q a = [ q 1 , q 2 , , q n ] . The structures of the different robots are shown in Figure 1, and the DH parameters of the corresponding manipulator robot are shown in Table 3.
When we establish the gravity center at the coordinate system of the mobile platform, the distances from the base-fixed coordinate frame to the mobile-fixed coordinate frame are dx1, dy2, dz3, dx1, dy2, dz3, dx1, dy2, dz3. Therefore, the homogeneous matrix from the center position to the end could be expressed as:
T c b 1 = [ 1 0 0 0.167 0 1 0 0.000 0 0 1 0.225 0 0 0 1 ] ; T c b 2 = [ 1 0 0 0.450 0 1 0 0.000 0 0 1 0.325 0 0 0 1 ] ; T c b 3 = [ 1 0 0 0.450 0 1 0 0.000 0 0 1 0.325 0 0 0 1 ]
At the initial moment, the position of the mobile platform is set to (0, 0, 0), the angles of the first manipulator subsystem are set to (0, 0, 0, 0, 0), the angles of the second manipulator subsystem are set to (0, 0, 0, 0, 0, 0), and the initial angles of the third manipulator subsystem are to as (0, 0, 0, 0, 0, 0, 0). In this case, the corresponding limit ranges of the mobile manipulator are, respectively, expressed as:
R o b o t 1 : { q L = [ 1 . 5 , 1 . 5 , pi , 169 , 65 , 150 , 102 . 5 , 167 . 5 ] q U = [ + 1 . 5 , + 1 . 5 , + pi , + 169 , + 90 , + 146 , + 102 . 5 , + 167 . 5 ]
R o b o t 2 : { q L = [ 1 . 5 , 1 . 5 , pi , 169 , 165 , 150 , 102 . 5 , 167 . 5 , 167 . 5 ] q U = [ + 1 . 5 , + 1 . 5 , + pi , + 169 , + 165 , + 150 , + 102 . 5 , + 167 . 5 , + 167 . 5 ]
R o b o t 3 : { q L = [ 1 . 5 , 1 . 5 , pi , 169 , 120 , 170 , 120 , 170 , 120 , 170 ] q U = [ + 1 . 5 , + 1 . 5 , + pi , + 169 , + 120 , + 170 , + 120 , + 170 , + 120 , + 170 ]

5.2. The Best Differential Evolution Test

The problem dimension D is set according to the number of driving joints of the mobile manipulator. The dimensions for robot1, robot2, and robot3 are 8, 9, and 10, respectively. The maximum number of iterations is set to G = 1000 . When the error between the solution result and the actual task is less than 10 8 , the error value is set to 0, and the robot could successfully complete the task point, so then needed to solve the next task point. Most control parameters of these DE algorithms are set to the same value as in the original study, and each algorithm’s control parameter settings are shown in Table 4.
Where the parameter L in the ISAMDE algorithm is the threshold value. It is used to record the numbers of current best solution is updated and not updated.

5.2.1. Fixed Point Task

To test the performance of the various DE algorithms, we first randomly design 100 target points (Task 1) without the mobile platform’s movement as the study objects. The given target point contained position and posture information; we specifically compare the performance of the various algorithms. To ensure that the target point is in the working space of the robot, we use the Monte Carlo method to generate multiple random numbers within the given joint angle constraints. To test the performance regarding inverse kinematics, we first determine many driving joint angles by randomly selecting from among the given angle range. Then, the position and posture of the fixed-point tasks are generated by the forward kinematics of the mobile manipulator robot, which could be expressed as:
{ T e = F K ( d x , d y , q z , q 1 , q 2 , , q n ) d x = d y = d z = 0 q i = q l ( i ) + ( q u ( i ) q l ( i ) ) r a n d
We perform multiple iterations on the fixed-point task. To simultaneously determine the above position and state, we choose the F2 fitness function to solve the calculation. To improve the efficiency of the solution, the final decision function F1 is transferred to the system. The specific parameters are expressed as:
{ f i t : F 2 = f 2 ( q ) s t o p : F 1 = f 1 ( q )
The number of populations is set N P = 50; F = 0.5, and C R = 0.9; the corresponding number of iterations is G = 1000. We compare the various key parameters of inverse kinematics including the average time for each iteration; the error range, success rate of the solution, and the corresponding results are summarized in Table 5.
The results of the first simulation for the manipulators with different degrees of freedom are shown in Figure 4. Given these 100 random task points including posture and position, we compare the total error and calculation time. We obtain the following results:
(1)
A comparison of the total error in Figure 4a,c,e and Table 5 show that the success rate of the inverse kinematics solution for random points continue to increase with the continuous increase in the DOFs. Therefore, the high-DOF robot could more smoothly complete the complex task.
(2)
A comparison of the times in Figure 4b,d,f show that in most situations, the calculation speed of best1, best2, cube, AMDE, NSDE, JDE and ISAMDE are faster when solving random task points. The above methods are relatively close in time. The inverse kinematics mean time of robot1, robot2, and robot3 takes near 0.2 s, 0.4 s, 0.5 s, respectively. On the contrary, CODE and JADE need the longest time to produce a solution, and the mean time for robot1, robot2, and robot3 to obtain a solution are longer than 2 s. Follow the best1, best2, cube, AMDE, NSDE, JDE and ISAMDE algorithm, the PDcDE algorithm shows faster convergence rate and less time comsumption than the other algorithms for robot1, robot2 and robot3. Then, rand1, ODE and ENMDE are located at the third level, requiring 0.8 s, 1 s, and 1.5 s to solve the tasks for robot1, robot2, and robot3, respectively.
Where 12, 13, 14 in the Figure 4 represent “ISAMDE”, “ENMDE” and “PDcDE”, respectively.

5.2.2. Trajectory Tracking Test

Because the mobile manipulator need to complete different tasks, the test results of a single fixed point could complete the continuous performance test. Therefore, we choose two typical motion trajectories to compare the energy absorption of the IK of the mobile robot. The first trajectory is a simple COS trajectory (Task 2), and the second one is a complex spiral trajectory (Task 3), which is shown in Figure 5. The mathematical expression of these trajectoriess can be expressed as:
{ x 1 a = 0.5 y 1 a = t / N z 1 a = 0.4 + 0.15 cos ( 4 π t / N ) ; { x 2 a = 0.5 y 2 a = t / N z 2 a = 0.8 + 0.15 cos ( 4 π t / N ) ; { x 3 a = 0.5 y 3 a = t / N z 3 a = 0.9 + 0.15 cos ( 4 π t / N )
{ x 1 b = t / N y 1 b = 0.15 sin ( 4 π t / N ) z 1 b = 0.4 + 0.15 cos ( 4 π t / N ) ; { x 2 b = t / N y 2 b = 0.15 sin ( 4 π t / N ) z 2 b = 0.8 + 0.15 cos ( 4 π t / N ) ; { x 3 b = t / N y 3 b = 0.15 sin ( 4 π t / N ) z 3 b = 0.9 + 0.15 cos ( 4 π t / N )
where x i a , y i a , z i a represents the position of the first desired trajectory corresponding to the i-th mobile manipulator robot, x i b , y i b , z i b represents the position of the second desired trajectory corresponding to the ith mobile manipulator robot, t = 1 s indicates the movement time for the desired trajectory, and N = 200 indicates the segmentation result for the desired trajectory.
For the first trajectory, we use the same parameters as in the first task (Task 1), which we design to compare the solution error and solution efficiency of these DE algorithms. Because the position requirement is without the posture requirement, the fitness function we used in the second task needed to be transformed, which could be specifically expressed as:
{ f i t : F 2 = f 3 ( q ) s t o p : F 1 = f 1 ( q )
where f 3 ( ) represents the minimum function of the sum of the position error and joint movement, and f 1 ( ) is the function that represents the smallest sum of the position errors.
The results of the task 2 simulation experiment for simple trajectory tracking are shown as Table 6. The trajectory tracking error and time required for the first trajectory tracking by the robots with different degrees of freedom are compared. Where Suc represents the numbers of success solution in the 200 trajectory points. By comparing these results, we obtained the following:
(1)
The total error shows that the tracking precision of the specified task point after moving the end of the robot arm substantially increased. The success rates of the cube, CODE and JADE algorithms for the IK problem of robot1 are lower than those of the other DE algorithms; the success rates of CODE, JADE, ENMDE, and PDcDE for the IK problem of robot2 are lower than those of the other DE algorithms; the success rates of cube, JADE, ENMDE and PDcDE for the inverse kinematics of robot3 are lower than those of the other DE algorithms.
(2)
Comparing the solution mean time in Table 6 shows that best1 and ISAMDE have better performance for the IK of all robots. However, CODE, JADE and ENMDE perform worse for the inverse kinematics of all robots. Additionally, the solution performance of the other algorithms for the different robots are in between.
For the second trajectory, we use the same parameters as in Task 2, which we design for the various DE algorithms to compare their solution error and solution efficiency. The results of the third simulation experiment for the complex trajectory tracking task are shown in Table 7. The trajectory tracking error and overall time-consuming tactics of the mobile manipulators with different degrees of freedom are presented. We obtain the following:
(1)
Comparing the error parameters in Table 6 and Table 7, we find that the success rate and error of these DE algorithms for solving the medium-complexity trajectory tracking task are widely different. This is caused by the DOFs of the robot and the complexity of the task points. The error range of the various algorithms for robot2 narrowed, but the solution error of best2, cube, and JADE algorithm increases.
(2)
By comparing the calculation speeds (mean time) shown in Table 7, we find that best1, AMDE and ISAMDE perform the best, the mean time of the three algorithms are less than 0.5 s for all the robots; CODE, JADE and ENMDE perform the worst, in most situations, the mean time are more than 2 s. The solution performance of the other algorithms for the different robots is between the best DE algorithms and worst DE algorithms.
(3)
A comparison of the solution time and overall error in Table 7 shows that the solution performance of the different methods differ for the different robots. JADE and ENMDE perform worst on all robots, rand1, best1, AMDE and ISAMDE perform the best on all robots.

5.3. Optimization of Best DE Algorithm

In various differential evolution algorithms, mutation operators and crossover operators are important factors for the algorithm. However, for the determined optimal DE algorithm, mutation operators and crossover operators are fixed parameters. We have determined the best DE method for solving the IK of mobile manipulators with different DOFs. As we generally known, the best DE algorithm will also be affected by the crossover probability and mutation factor in the solution process. To further improve the best DE, we can consider the specific impact of the control parameters and population size. Therefore, we optimize the performance of the best differential evolution algorithm for the IK problem of various mobile manipulators based on the selection of the control parameters and population size. The parameter optimization process applies to all algorithms. In this paper, we select the best DE algorithm to compare and introduce the optimization process. The process of determining the best DE algorithm can be described as: Firstly, compare the success rate in the fixed task (Table 5), the more DOFs of robot has, the more complex of solving process will be. If the solution of one algorithm is outperform in solving complex problem, the algorithm is better. So we analyse the performance of robot and choose the best performance of all the algorithms as the best DE algorithm. Then, compare the maximum value of error, if the error is smaller, the algorithm is better, finally, compare the maximum time, if the time is smaller, the algorithm is better. In this way, we select the AMDE algorithm as the best DE algorithm.

5.3.1. Variation Factor

To determine the best mutation factor F, we select eleven parameters from [0–1.1] as the mutation factor F and studied the effect of the mutation factor on the performance of the best differential evolution algorithm for solving the inverse kinematics. Then, we choose task 3 as the typical trajectory to be tracked, and the rest of the parameter settings remain unchanged except for the CR, which is set to 0.9. The total error and time used to solve the problem of the different variation factors are shown in Table 8. To avoid the influence of the crossover probability on the mutation factor, we again choose two different crossover probabilities to track the trajectory of task 3, which could be expressed as C R = 0.3 and C R = 0.6 . The specific results are shown in Table 9 and Table 10.
The results are compared for different variation factors considering a fixed C R of 0.9 and an N P of 50, as shown in Table 8. Among the best DE algorithms with different mutation parameters, the success rate of solving the inverse kinematics problem is between 0.3 and 0.8, and the error is close to 0. The range of the variation factor that required the shortest time for solving the inverse kinematics problem of the mobile manipulator is within [0.4–0.6], and whose mean time is less than 0.5 s. In this case, the setting range of the mutation factor in the best differential evolution algorithm is between 0.4 and 0.6, and the best setting value ranges from 0.4 to 0.5 for all mobile manipulator robots in this study.
To avoid the influence of crossover probability on the selection of mutation factors, we choose two different crossover probabilities to perform trajectory tracking on task 3 again, and the corresponding simulation results are shown in Table 9 and Table 10. By comparing the mean error in Table 8, Table 9 and Table 10, we find that the performance of the best DE algorithm with same mutation factor gradually improves as the crossover probability increases from 0.3 to 0.9.
Comparing the times in Table 8, Table 9 and Table 10, we find that the time required to reach a solution of the best DE algorithm substantially differs among the robots when the crossover probability is set at 0.9. For robot2, we find no notable difference in the mean time of the best DE algorithm when the crossover probability is set to 0.3 or 0.6, but most algorithms require more time than the previous setting.

5.3.2. Crossover Probability

To determine the best crossover probability (CR), we continuously select ten parameters within [0–1] as the CR and study the impact of the CR in solving inverse kinematics. Then, we choose task 3 as the typical trajectory to be tracked; the rest of the parameter settings remain unchanged except the variation factor, which is set to F = 0.4.
Comparing the total error in Table 11, The results show that the best DE algorithm with same variation factor improved as the crossover probability increases from 0.6 to 0.9. Outside this range, the success rate of the IK solution of these mobile manipulator robots substantially reduce, and the trajectory tracking error is relatively large. By comparing the mean times in Table 11, we find that the solution mean time and maximum time of the best DE algorithm are markedly different for all robots when the C R is set to (0.9–1.0). However, when the C R is set to 0.1 and 0.5, the time of the best DE algorithm is the longest and does not differ much. The solution time of the best DE algorithm gradually decreases as the crossover factor changed from 0.7 to 0.9; the crossover probability of the best differential evolution algorithm is best in the range of (0.7–0.9).

5.3.3. Population Size

To determine the best population size (NP), we continuously select eleven parameters from 20 to 70 as the population size to study the impact of NP on solving the IK problem. We also choose task 3 as the typical trajectory to be tracked by the end effector, F is set to 0.4, C R is set to 0.9, and the rest of the parameter settings remain unchanged. The total error and time used to solve the problem with different variation factors are shown in Table 12.
A comparison of the total error in Table 12 shows that the DE algorithm performs the best when the population size is more than 25, and the trajectory tracking error is relatively small. Comparing the times in Table 12 shows that the average time required by the best DE algorithm first increases to a plateau and then gradually decreases for robot1 and robot2 as the population size increases from 20 to 70. For robot1, the average time requires to reaction a solution of the best DE algorithm does not notably change. However, the average time of the best DE algorithm is less than 0.5 s for all robots when the population size is more than 60. To ensure diversity, we set the optimal population size of the best DE algorithm to (60–70) for these mobile manipulator robots.

6. Conclusions

In this study, we compare the performance of various DE algorithms when dealing with the IK problem of mobile manipulator robots. We investigate the specific optimization techniques of various DE algorithms to guide future improvements in the DE algorithm. As the most important problem, IK becomes increasingly difficult with an increase in the DOFs. Therefore, we define the IK of a mobile manipulator as a variety of global optimal problem functions according to different task requirements. To determine the best DE algorithm for solving the problem, various DE algorithms are used to solve the IK problem of mobile manipulators with different DOFs. We further improve the performance of the best DE algorithm based on the specific influence of the different parameters on the DE algorithm.
In the future, we aim to design a new DE algorithm with better performance to solve the IK problem. We will use the DE algorithm to achieve path planning and trajectory tracking for mobile manipulator robots with physical limitations in complex environments.

Author Contributions

Conceptualization, M.L. and L.Q.; methodology, M.L. and L.Q.; software, M.L. and L.Q.; validation, L.Q.; formal analysis, M.L. and L.Q.; investigation, M.L. and L.Q.; resources, L.Q.; data curation, M.L.; writing—original draft preparation, M.L. and L.Q.; writing—editing, L.Q.; visualization, M.L.; supervision, M.L.; project administration, M.L. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Park, D.; Hoshi, Y.; Mahajan, H.P.; Kim, H.K.; Erickson, Z.; Rogers, W.A.; Kemp, C.C. Active robot-assisted feeding with a general-purpose mobile manipulator: Design, evaluation, and lessons learned. Robot. Auton. Syst. 2020, 124, 103344. [Google Scholar] [CrossRef]
  2. Meng, X.; He, Y.; Han, J. Survey on Aerial Manipulator: System, Modeling, and Control. Robot. Auton. Syst. 2019, 38, 1288–1317. [Google Scholar] [CrossRef]
  3. Stibinger, P.; Broughton, G.; Majer, F.; Rozsypalek, Z.; Wang, A.; Jindal, K.; Zhou, A.; Thakur, D.; Loianno, G.; Krajnik, T.; et al. Mobile Manipulator for Autonomous Localization, Grasping and Precise Placement of Construction Material in a Semi-Structured Environment. IEEE Robot. Autom. Lett. 2021, 6, 2595–2602. [Google Scholar] [CrossRef]
  4. Hamner, B.; Koterba, S.; Shi, J.; Simmons, R.; Singh, S. An autonomous mobile manipulator for assembly tasks. Auton. Robot. 2010, 28, 131–149. [Google Scholar] [CrossRef]
  5. Huang, H.; Tang, Q.; Li, J.; Zhang, W.; Bao, X.; Zhu, H.; Wang, G. A review on underwater autonomous environmental perception and target grasp, the challenge of robotic organism capture. Ocean Eng. 2020, 195, 106644. [Google Scholar] [CrossRef]
  6. Jain, A.; Kemp, C.C. EL-E: An assistive mobile manipulator that autonomously fetches objects from flat surfaces. Auton. Robot. 2010, 28, 45–64. [Google Scholar] [CrossRef]
  7. Engemann, H.; Du, S.; Kallweit, S.; Cönen, P.; Dawar, H. OMNIVIL—An Autonomous Mobile Manipulator for Flexible Production. Sensors 2020, 20, 7249. [Google Scholar] [CrossRef] [PubMed]
  8. Liao, J.; Huang, F.; Chen, Z.; Yao, B. Optimization-based motion planning of mobile manipulator with high degree of kinematic redundancy. Sensors 2019, 3, 115–130. [Google Scholar] [CrossRef]
  9. Santos, P.C.; Freire, R.C.S.; Carvalho, E.A.N.; Molina, L.; Freire, E.O. M-FABRIK: A New Inverse Kinematics Approach to Mobile Manipulator Robots Based on FABRIK. IEEE Access 2020, 8, 208836–208849. [Google Scholar] [CrossRef]
  10. Galicki, M. Control-based solution to inverse kinematics for mobile manipulators using penalty functions. J. Intell. Robot. Syst. Theory Appl. 2005, 42, 213–238. [Google Scholar] [CrossRef]
  11. Raja, R.; Dutta, A.; Dasgupta, B. Learning framework for inverse kinematics of a highly redundant mobile manipulator. Robot. Auton. Syst. 2019, 120, 103245. [Google Scholar] [CrossRef]
  12. El-Sherbiny, A.; Elhosseini, M.A.; Haikal, A.Y. A comparative study of soft computing methods to solve inverse kinematics problem. Ain Shams Eng. J. 2018, 9, 2535–2548. [Google Scholar] [CrossRef]
  13. Zhang, Y.; Lv, X.; Li, Z.; Yang, Z.; Chen, K. Repetitive motion planning of PA10 robot arm subject to joint physical limits and using LVI-based primal-dual neural network. Mechatronics 2008, 18, 475–485. [Google Scholar] [CrossRef]
  14. Galicki, M. Real-time constrained trajectory generation of mobile manipulators. Robot. Auton. Syst. 2016, 78, 49–62. [Google Scholar] [CrossRef]
  15. Kofinas, N.; Orfanoudakis, E.; Lagoudakis, M.G. Complete Analytical Forward and Inverse Kinematics for the NAO Humanoid Robot. J. Intell. Robot. Syst. Theory Appl. 2015, 77, 251–264. [Google Scholar] [CrossRef]
  16. Tchoń, K.; Jakubiak, J. Extended Jacobian inverse kinematics algorithm for nonholonomic mobile robots. International Journal of Control 2006, 79, 895–909. [Google Scholar] [CrossRef]
  17. Xiao, L.; Zhang, Y. Solving time-varying inverse kinematics problem of wheeled mobile manipulators using Zhang neural network with exponential convergence. Nonlinear Dyn. 2014, 76, 1543–1559. [Google Scholar] [CrossRef]
  18. Hassan, A.A.; El-Habrouk, M.; Deghedie, S. Inverse Kinematics of Redundant Manipulators Formulated as Quadratic Programming Optimization Problem Solved Using Recurrent Neural Networks: A Review. Robotica 2020, 38, 1495–1512. [Google Scholar] [CrossRef]
  19. Jin, L.; Li, S.; Yu, J.; He, J. Robot manipulator control using neural networks: A survey. Neurocomputing 2018, 285, 23–34. [Google Scholar] [CrossRef]
  20. Zhang, Z.; Zhang, Y. Variable joint-velocity limits of redundant robot manipulators handled by quadratic programming. IEEE/ASME Trans. Mechatron. 2013, 18, 674–686. [Google Scholar] [CrossRef]
  21. Zhang, Z.; Zheng, L.; Yu, J.; Li, Y.; Yu, Z. Three recurrent neural networks and three numerical methods for solving a repetitive motion planning scheme of redundant robot manipulators. IEEE/ASME Trans. Mechatron. 2017, 1423–1434. [Google Scholar] [CrossRef]
  22. Nonoyama, K.; Liu, Z.; Fujiwara, T.; Alam, M.M.; Nishi, T. Energy-Efficient Robot Configuration and Motion Planning Using Genetic Algorithm and Particle Swarm Optimization. Energies 2022, 15, 2074. [Google Scholar] [CrossRef]
  23. Mancilla, A.; García-Valdez, M.; Castillo, O.; Merelo-Guervós, J.J. Optimal Fuzzy Controller Design for Autonomous Robot Path Tracking Using Population-Based Metaheuristics. Symmetry 2022, 14, 202. [Google Scholar] [CrossRef]
  24. Safarini, O.A.S. Analytical study of algorithms for solving inverse kinematic problems in robot motion control systems. Int. J. Adv. Comput. Sci. Appl. 2018, 9, 57–61. [Google Scholar] [CrossRef]
  25. Dulźba, I.; Opałka, M. A comparison of jacobian-based methods of inverse kinematics for serial robot manipulators. Int. J. Appl. Math. Comput. Sci. 2013, 23, 373–382. [Google Scholar] [CrossRef]
  26. Duleba, I.; Karcz-Duleba, I. A comparison of methods solving repeatable inverse kinematics for robot manipulators. Arch. Control. Sci. 2018, 28, 5–18. [Google Scholar] [CrossRef]
  27. Köker, R.; Öz, C.; Çakar, T.; Ekiz, H. A study of neural network based inverse kinematics solution for a three-joint robot. Robot. Auton. Syst. 2004, 49, 227–234. [Google Scholar] [CrossRef]
  28. 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. Procedia CIRP 2014, 17, 812–817. [Google Scholar] [CrossRef]
  29. Sari, Y. Performance evaluation of the various training algorithms and network topologies in a neural-Network-Based inverse kinematics solution for robots. Int. J. Adv. Robot. Syst. 2014, 11, 1–10. [Google Scholar] [CrossRef]
  30. Xiao, L.; Zhang, Y. Acceleration-level repetitive motion planning and its experimental verification on a six-link planar robot manipulator. IEEE Trans. Control. Syst. Technol. 2013, 21, 906–914. [Google Scholar] [CrossRef]
  31. Zhang, Z.; Kong, L.; Yan, Z.; Chen, K.; Li, S.; Qu, X.; Tan, N. Comparisons among Six Numerical Methods for Solving Repetitive Motion Planning of Redundant Robot Manipulators. In Proceedings of the 2018 IEEE International Conference on Robotics and Biomimetics, ROBIO, Kuala Lumpur, Malaysia, 12–15 December 2018; pp. 1645–1652. [Google Scholar] [CrossRef]
  32. Zhang, Z.; Zhang, Y. Acceleration-level cyclic-motion generation of constrained redundant robots tracking different paths. IEEE Trans. Syst. Man, Cybern. Part B Cybern. 2012, 42, 1257–1269. [Google Scholar] [CrossRef] [PubMed]
  33. Nguyen-Van, S.; Lieu, Q.X.; Xuan-Mung, N.; Nguyen, T.T.N. A New Study on Optimization of Four-Bar Mechanisms Based on a Hybrid-Combined Differential Evolution and Jaya Algorithm. Symmetry 2022, 14, 381. [Google Scholar] [CrossRef]
  34. Ayyıldız, M.; Çetinkaya, K. Comparison of four different heuristic optimization algorithms for the inverse kinematics solution of a real 4-DOF serial robot manipulator. Neural Comput. Appl. 2016, 27, 825–836. [Google Scholar] [CrossRef]
  35. Zhang, J.H.; Zhang, Y.; Zhou, Y. Path planning of mobile robot based on hybrid multi-objective bare bones particle swarm optimization with differential evolution. IEEE Access 2018, 6, 44542–44555. [Google Scholar] [CrossRef]
  36. Yi, W.; Lin, Z.; Lin, Y.; Xiong, S.; Yu, Z.; Chen, Y. Solving Optimal Power Flow Problem via Improved Constrained Adaptive Differential Evolution. Mathematics 2023, 11, 1250. [Google Scholar] [CrossRef]
  37. Nguyen, T.T.; Vu Quynh, N.; Duong, M.Q.; Van Dai, L. Modified Differential Evolution Algorithm: A Novel Approach to Optimize the Operation of Hydrothermal Power Systems while Considering the Different Constraints and Valve Point Loading Effects. Energies 2018, 11, 540. [Google Scholar] [CrossRef]
  38. Yu, Y.; Wang, K.; Zhang, T.; Wang, Y.; Peng, C.; Gao, S. A Population Diversity-Controlled Differential Evolution for Parameter Estimation of Solar Photovoltaic Models. Sustain. Energy Technol. Assess. 2022, 51, 101938. [Google Scholar] [CrossRef]
  39. Hern, ez-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, 1–30. [Google Scholar] [CrossRef]
  40. Zhang, Q.; Wang, D.; Gao, L. Research on the inverse kinematics of manipulator using an improved self-adaptive mutation differential evolution algorithm. Int. J. Adv. Robot. Syst. 2021, 18, 1–11. [Google Scholar] [CrossRef]
  41. Rodriguez, E.; Saha, B.N.; Romero-Hdz, J.; Ortega, D. A Multi-objective Differential Evolution Algorithm for Robot Inverse Kinematics. Int. J. Comput. Sci. Eng. 2016, 3, 71–79. [Google Scholar] [CrossRef]
  42. Ren, Z.; Li, C.; Sun, L. Minimum-acceleration trajectory optimization for humanoid manipulator based on differential evolution. Int. J. Adv. Robot. Syst. 2016, 13, 73. [Google Scholar] [CrossRef]
  43. 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, 1–22. [Google Scholar] [CrossRef]
  44. Liu, J.; Lampinen, J. A fuzzy adaptive differential evolution algorithm. Soft Comput. 2005, 9, 448–462. [Google Scholar] [CrossRef]
  45. Qin, A.K.; Huang, V.L.; Suganthan, P.N. Differential evolution algorithm with strategy adaptation for global numerical optimization. IEEE Trans. Evol. Comput. 2009, 13, 398–417. [Google Scholar] [CrossRef]
  46. Qin, A.K.; Suganthan, P.N. Self-adaptive differential evolution algorithm for numerical optimization. In Proceedings of the 2005 IEEE Congress on Evolutionary Computation, IEEE CEC 2005, Edinburgh, UK, 2–5 September 2005; Volume 2, pp. 1785–1791. [Google Scholar] [CrossRef]
  47. Wang, S.; Li, Y.; Yang, H.; Liu, H. Self-adaptive differential evolution algorithm with improved mutation strategy. Soft Comput. 2018, 22, 3433–3447. [Google Scholar] [CrossRef]
  48. Brest, J.; Greiner, S.; Bošković, B.; Mernik, M.; Zumer, V. Self-adapting control parameters in differential evolution: A comparative study on numerical benchmark problems. IEEE Trans. Evol. Comput. 2006, 10, 646–657. [Google Scholar] [CrossRef]
  49. Zhang, J.; Sanderson, A.C. JADE: Adaptive differential evolution with optional external archive. IEEE Trans. Evol. Comput. 2009, 13, 945–958. [Google Scholar] [CrossRef]
  50. Cui, L.; Li, G.; Zhu, Z.; Ming, Z.; Wen, Z.; Lu, N. Differential evolution algorithm with dichotomy-based parameter space compression. Soft Comput. 2019, 23, 3643–3660. [Google Scholar] [CrossRef]
  51. Wang, Y.; Cai, Z.; Zhang, Q. Differential evolution with composite trial vector generation strategies and control parameters. IEEE Trans. Evol. Comput. 2011, 15, 55–66. [Google Scholar] [CrossRef]
  52. Fan, S.; Xie, X.; Zhou, X. Optimum manipulator path generation based on improved differential evolution constrained optimization algorithm. Int. J. Adv. Robot. Syst. 2019, 16, 1–12. [Google Scholar] [CrossRef]
  53. Deng, W.; Shang, S.; Cai, X.; Zhao, H.; Song, Y.; Xu, J. An improved differential evolution algorithm and its application in optimization problem. Soft Computing. 2021, 25, 5277–5298. [Google Scholar] [CrossRef]
  54. Wang, H.; Wu, Z.; Rahnamayan, S.; Kang, L. A scalability test for accelerated de using generalized opposition-based learning. In Proceedings of the ISDA 2009—9th International Conference on Intelligent Systems Design and Applications, Pisa, Italy, 30 November–2 December 2009; Volume 2, pp. 1090–1095. [Google Scholar] [CrossRef]
  55. Yu, Y.; Zhu, A.; Zhu, Z.; Lin, Q.; Yin, J.; Ma, X. Multifactorial Differential Evolution with Opposition-based Learning for Multi-tasking Optimization. In Proceedings of the 2019 IEEE Congress on Evolutionary Computation, CEC 2019—Proceedings, Wellington, New Zealand, 10–13 June 2019; pp. 1898–1905. [Google Scholar] [CrossRef]
Figure 1. Kinematic modeling of mobile manipulator robot: (a) side view and corresponding frames; (b) top view and corresponding frames.
Figure 1. Kinematic modeling of mobile manipulator robot: (a) side view and corresponding frames; (b) top view and corresponding frames.
Symmetry 15 01080 g001
Figure 2. Flowchart of the DE algorithm used in solving the inverse kinematics.
Figure 2. Flowchart of the DE algorithm used in solving the inverse kinematics.
Symmetry 15 01080 g002
Figure 3. Structure of different types of mobile manipulator robots: (a) 5 DOF arm, (b) 6 DOF arm, and (c) 7 DOF arm.
Figure 3. Structure of different types of mobile manipulator robots: (a) 5 DOF arm, (b) 6 DOF arm, and (c) 7 DOF arm.
Symmetry 15 01080 g003
Figure 4. Performance comparison of inverse kinematics solution for random points. (a) the total fitness value for solving the inverse kinematics of the mobile manipulator robot with 5 DOF arm. (b) the total time comsumption for solving the inverse kinematics of the mobile manipulator robot with 5 DOF arm. (c) the total fitness value for solving the inverse kinematics of the mobile manipulator robot with 6 DOF arm. (d) the total time comsumption for solving the inverse kinematics of the mobile manipulator robot with 6 DOF arm. (e) the total fitness value for solving the inverse kinematics of the mobile manipulator robot with 7 DOF arm. (f) the total time comsumption for solving the inverse kinematics of the mobile manipulator robot with 7 DOF arm.
Figure 4. Performance comparison of inverse kinematics solution for random points. (a) the total fitness value for solving the inverse kinematics of the mobile manipulator robot with 5 DOF arm. (b) the total time comsumption for solving the inverse kinematics of the mobile manipulator robot with 5 DOF arm. (c) the total fitness value for solving the inverse kinematics of the mobile manipulator robot with 6 DOF arm. (d) the total time comsumption for solving the inverse kinematics of the mobile manipulator robot with 6 DOF arm. (e) the total fitness value for solving the inverse kinematics of the mobile manipulator robot with 7 DOF arm. (f) the total time comsumption for solving the inverse kinematics of the mobile manipulator robot with 7 DOF arm.
Symmetry 15 01080 g004
Figure 5. The structure of different types of mobile manipulator robots. (a) Trajectory tracking task 2 for the robot with 5 DOF arm. (b) Trajectory tracking task 3 for the robot with 5 DOF arm. (c) Trajectory tracking task 2 for the robot with 6 DOF arm. (d) Trajectory tracking task 3 for the robot with 6 DOF arm. (e) Trajectory tracking task 2 for the robot with 7 DOF arm. (f) Trajectory tracking task 3 for the robot with 7 DOF arm.
Figure 5. The structure of different types of mobile manipulator robots. (a) Trajectory tracking task 2 for the robot with 5 DOF arm. (b) Trajectory tracking task 3 for the robot with 5 DOF arm. (c) Trajectory tracking task 2 for the robot with 6 DOF arm. (d) Trajectory tracking task 3 for the robot with 6 DOF arm. (e) Trajectory tracking task 2 for the robot with 7 DOF arm. (f) Trajectory tracking task 3 for the robot with 7 DOF arm.
Symmetry 15 01080 g005
Table 1. The pseudocode of self-tuned mutation strategy.
Table 1. The pseudocode of self-tuned mutation strategy.
Self-Tuned Mutation
If Δ F T d > Δ F T m e a n
if r a n d > M M F
v = x r 1 + F ( x r 2 x r 3 )
else
v = x r 1 + F ( x r 2 x r 3 + x r 4 x r 5 )
end
else
if r a n d > M M F
v = x b e s t + F ( x r 2 x r 3 )
else
v = x b e s t + F ( x r 2 x r 3 + x r 4 x r 5 )
end
end
Table 2. Specific optimization content of different DE algorithms.
Table 2. Specific optimization content of different DE algorithms.
NameInitial PopulationVariation FactorCrossover ProbabilityMutation OperatorCrossover Operator
A1TDE――――――OptimizeOptimize
A2ODEOptimize――――――――
A3CODE――Optimize――Optimize――
A4AMDE――――――OptimizeOptimize
B1NSDE――Optimize――――――
C1JDEOptimizeOptimizeOptimize――――
C2JADE――OptimizeOptimizeOptimize――
C3SADE――OptimizeOptimizeOptimize――
C4ISAMDE――Optimize――Optimize――
C5ENMDE――――OptimizeOptimize――
C6PDcDE――Optimize――Optimize――
Table 3. Standard parameters of the manipulator subsystem.
Table 3. Standard parameters of the manipulator subsystem.
5 Dof Arm6 Dof Arm7 Dof Arm
joint i d i a i α i joint i d i a i α i joint i d i a i α i
10.1470.033 π / 2 10.8950 π / 2 10.3600 π / 2
20.0000.155020−0.4250200 π / 2
30.0000.135030−0.392030.4200 π / 2
40.0000.000 π / 2 41.0920 π / 2 400 π / 2
50.0000.000050.9470 π / 2 50.4000 π / 2
60.82300600 π / 2
70.12600
Table 4. The parameter settings for each DE algorithm.
Table 4. The parameter settings for each DE algorithm.
NameNumberParameter Setting
rand101 G = 1000 ; N P = 50 ; F = 0.5 ; C R = 0.9 ;
best102 G = 1000 ; N P = 50 ; F = 0.5 ; C R = 0.9 ;
rand203 G = 1000 ; N P = 50 ; F = 0.5 ; C R = 0.9 ;
best204 G = 1000 ; N P = 50 ; F = 0.5 ; C R = 0.9 ;
cu-be05 G = 1000 ; N P = 50 ; F = 0.5 ; C R = 0.9 ;
ODE06 G = 1000 ; N P = 50 ; F = 0.5 ; C R = 0.9 ;
CODE07 G = 1000 ; N P = 50 ; F = 0.5 ; C R = 0.9 ;
AMDE08 G = 1000 ; N P = 50 ; F = [ 1.0 , 1.0 , 0.8 ] ; C R = [ 0.1 , 0.9 , 0.2 ] ;
NSDE09 G = 1000 ; N P = 50 ; F = { N o r m r n d ( 0.5 , 0.5 ) | | C a u c h y r n d ( 1 ) } ; C R = 0.9 ;
JDE10 G = 1000 ; N P = 50 ; F = 0.1 + 0.9 r a n d ; C R = r a n d ;
JADE11 G = 1000 ; N P = 50 ; N b = 5 ; u F = 0.6 ; u C R = 0.85 ;
ISAMDE12 G = 1000 ; N P = 50 ; F = 0.5 ; C R = 0.9 ;
ENMDE13 G = 1000 ; N P = 50 ; F = 0.5 ; C R = 1 ; M M F = 0.25 ;
PDcDE14 G = 1000 ; N P = 50 ; N m a x = 55 ; N m i n = 45 ; L = 5 ; F = 0.5 ; C R = 0.9
Table 5. The basic results for solving inverse kinematics of the different mobile manipulator robots.
Table 5. The basic results for solving inverse kinematics of the different mobile manipulator robots.
NameErrorTimeSuc
RobotDEMinMeanMaxMinMeanMaxSuc
robot1010 1.2 × 10 3 0.0840.5480.7071.56698
020 1.4 × 10 2 0.2660.0860.3681.65784
03 1.1 × 10 6 1.0 × 10 3 0.0501.6221.6401.70790
040 8.0 × 10 3 0.2510.2890.4841.72591
050 1.2 × 10 2 0.2340.2000.5171.74583
060 2.3 × 10 3 0.1710.6270.8061.97798
070 1.9 × 10 3 0.0441.2094.1764.99581
080 1.1 × 10 2 0.1790.2150.4441.70387
090 1.3 × 10 2 0.2850.2230.6942.54084
100 1.3 × 10 2 0.2000.1840.5561.71983
11 5.9 × 10 4 9.0 × 10 3 0.0793.9053.9804.3502
120 1.4 × 10 3 0.1550.2100.2590.74097
130 8.7 × 10 3 0.1980.6651.1663.05186
140 8.4 × 10 3 0.2300.4390.7031.82294
robot201 1.7 × 10 7 3.9 × 10 4 0.0580.7651.0451.80899
020 5.9 × 10 3 0.2070.1000.2411.87595
03 2.5 × 10 3 2.9 × 10 2 0.2651.8591.8881.9423
040 3.5 × 10 3 0.4670.3750.5201.93699
050 9.3 × 10 3 0.3100.1630.3531.94193
060 1.4 × 10 7 9.3590.8561.1131.992100
070 3.2 × 10 4 0.0111.1794.3895.65092
080 6.3 × 10 3 0.2920.3030.4281.93195
090 6.8 × 10 3 0.1950.2550.5362.79794
100 3.9 × 10 3 0.4270.2240.4021.92398
11 1.4 × 10 3 1.5 × 10 2 0.0574.2944.3734.5290
120000.2750.3210.525100
130 3.3 × 10 3 0.1920.8931.2563.60993
140 8.1 × 10 3 0.4190.4780.8242.38995
robot3010 1.2 × 10 5 1.2 × 10 3 1.0971.4111.95299
020000.1260.1800.824100
03 1.7 × 10 3 1.5 × 10 1 3.1 × 10 1 2.0682.0872.1560
040 2.7 × 10 5 2.7 × 10 3 0.2110.3162.13399
050 4.8 × 10 4 4.4 × 10 2 0.3100.4842.10898
060 1.1 × 10 5 1.1 × 10 3 1.0961.4322.38699
07 6.1 × 10 1 2.55.05.8835.9506.4560
080000.1400.1810.675100
090000.3150.4472.515100
100 6.5 × 10 6 5.5 × 10 4 0.1470.3271.26598
11 1.3 × 10 3 1.1 × 10 2 3.7 × 10 2 4.4354.5394.6910
120 1.0 × 10 6 7.5 × 10 5 0.3360.3940.81299
130 3.0 × 10 4 2.2 × 10 2 1.0381.4914.16393
140 2.9 × 10 6 2.6 × 10 4 0.4830.7922.12298
Table 6. The comparison results of the first trajectory tracking for different mobile manipulator robots.
Table 6. The comparison results of the first trajectory tracking for different mobile manipulator robots.
NameErrorTimeSuc
RobotDEMinMeanMaxMinMeanMaxSuc
010000.0950.1180.234200
020000.0700.1130.273200
030000.6840.8330.957200
040000.1680.2240.319200
050 1 × 10 4 3.4 × 10 3 0.1140.4611.620161
060000.3300.4421.477200
robot1070 1.2 × 10 7 4.3 × 10 6 1.0311.9714.713162
080000.1410.1820.532200
090000.1610.2810.751200
100000.1230.2361.055200
110 4.0 × 10 4 6.1 × 10 3 3.7773.8313.9690
120000.1100.1530.323200
130 4.6 × 10 9 9.2 × 10 7 0.3300.6041.872199
140 4.5 × 10 8 3.8 × 10 6 0.3640.6761.706196
010 8.9 × 10 9 1.7 × 10 6 0.5170.6421.844199
020000.1040.3021.093200
030 6.1 × 10 5 1.2 × 10 2 1.3151.5681.881198
040000.2920.3871.240200
050 3.3 × 10 6 1.7 × 10 4 0.1890.6031.839194
060000.5760.7392.048200
robot2070 3.0 × 10 7 1.1 × 10 5 0.9913.0065.155140
080000.2170.3701.605200
090000.2770.7221.742200
100 6.5 × 10 8 1.1 × 10 5 0.2800.6791.875198
11 3.0 × 10 4 6.4 × 10 3 7.0 × 10 2 4.0944.1474.290
120000.1660.2070.571200
130 8.8 × 10 3 8.0 × 10 2 0.8333.0513.56623
140 1.2 × 10 5 4.1 × 10 4 0.4841.2982.164113
010000.5320.6791.388200
020000.1180.3010.748200
030 4.3 × 10 8 8.6 × 10 6 1.3381.7172.010198
040 6.0 × 10 4 4.4 × 10 2 0.1930.8481.966164
050 4.0 × 10 4 4.4 × 10 2 0.1881.1772.034118
060000.5710.7181.792200
070 5.6 × 10 8 3.7 × 10 6 1.8052.6915.806183
robot3080000.4780.6971.998200
090000.3030.6642.344200
100 5.1 × 10 7 6.1 × 10 5 0.2120.5891.238194
11 1.0 × 10 4 2.8 × 10 3 1.3 × 10 2 4.3484.4074.5400
120000.1620.1990.394200
130 7.1 × 10 3 1.1 × 10 1 0.9683.5554.11417
140 2.4 × 10 5 7.9 × 10 4 0.5951.3001.95180
Table 7. The comparison results of the second trajectory tracking for different mobile manipulator robots.
Table 7. The comparison results of the second trajectory tracking for different mobile manipulator robots.
NameErrorTimeSuc
RobotDEMinMeanMaxMinMeanMaxSuc
010000.2860.3600.466200
020000.0650.1080.299200
030000.6440.8040.923200
040000.7640.6250.879200
050 1.0 × 10 4 9.8 × 10 3 0.1130.3981.747171
060000.3540.4140.738200
070 1.5 × 10 7 3.8 × 10 6 1.0392.1434.852151
robot1080000.1390.1770.355200
090000.1700.2640.527200
100000.1210.2470.725200
11 4.3 × 10 7 1.5 × 10 5 7.1 × 10 4 3.8193.8633.9670
120000.1210.1580.354200
130 1.0 × 10 4 3.7 × 10 3 0.5341.6442.818115
140 5.6 × 10 8 5.0 × 10 6 0.3840.7431.869194
010000.5180.6291.021200
020000.1150.2900.851200
0307.1 × 10 8 1.3 × 10 5 1.2651.5411.855194
040 2.4 × 10 4 1.9 × 10 2 0.2870.4201.860196
0500 3.8 × 10 3 0.1650.5871.825197
060 6.1 × 10 9 1.2 × 10 6 0.5910.7742.244199
070 3.7 × 10 7 1.8 × 10 5 1.4302.9255.188150
robot2080000.2320.3561.092200
090000.3520.7251.792200
100 1.7 × 10 8 3.5 × 10 6 0.2960.6221.859199
11 2.0 × 10 4 6.9 × 10 3 3.8 × 10 2 4.0954.1514.3040
120000.1660.2000.381200
130 7.9 × 10 3 8.1 × 10 2 0.7922.8313.30232
140 1.0 × 10 4 1.4 × 10 2 0.5941.2431.861104
010000.5440.6361.152200
020000.1240.3251.128200
030 8.4 × 10 9 1.6 × 10 6 1.4391.6911.982199
040 5.0 × 10 4 2.9 × 10 2 0.1810.7362.023183
050 8.6 × 10 4 3.8 × 10 2 0.1991.3042.03396
060000.5660.7161.623200
070 8.4 × 10 8 3.0 × 10 6 1.7412.7275.689175
robot3080000.2340.3300.605200
090000.2820.6181.732200
100 3.7 × 10 6 5.5 × 10 4 0.1850.5571.177193
11 4.0 × 10 3 5.6 × 10 3 3.3 × 10 2 4.2294.4104.9320
120000.1610.1910.352200
130 9.0 × 10 3 1.0 × 10 1 1.0343.4954.35320
140 2.1 × 10 5 1.9 × 10 3 0.6561.3041.924107
Table 8. Influence of crossover factor on best DE algorithm with C R = 0.9, 5 DOF robot arm (robot1), 6 DOF robot arm (robot2), 7 DOF robot arm (robot3).
Table 8. Influence of crossover factor on best DE algorithm with C R = 0.9, 5 DOF robot arm (robot1), 6 DOF robot arm (robot2), 7 DOF robot arm (robot3).
NameErrorTimeSuc
RobotFMinMeanMaxMinMeanMaxSuc
0.10 2.1 × 10 2 3.1 × 10 1 0.0371.4443.05719
0.20 4.7 × 10 3 1.1 × 10 1 0.0520.7432.774126
0.30000.0930.2991.119200
0.40000.0990.1590.365200
0.50000.1400.1770.266200
robot10.60000.2010.2780.632200
0.70000.3080.4341.098200
0.80000.5520.6650.795200
0.90000.7661.0621.232200
10 2.0 × 10 4 2.8 × 10 2 0.6481.4991.60724
1.10 9.5 × 10 6 7.8 × 10 5 1.5331.6133.2952
0.10 1.3 × 10 2 3.2 × 10 1 0.0431.2411.98567
0.20 1.0 × 10 4 9.7 × 10 3 0.0800.4671.906181
0.30000.1310.4051.086200
0.40000.0530.1940.526200
0.50000.2280.3921.119200
robot20.60000.3530.4371.407200
0.70000.5990.7351.734200
0.80001.0001.2371.482200
0.90 5.1 × 10 7 5.1 × 10 6 1.6171.8241.93563
10 1.5 × 10 3 9.4 × 10 2 0.5981.7061.93147
1.1 4.5 × 10 6 4.9 × 10 4 3.7 × 10 3 1.8221.8431.9270
0.10 1.6 × 10 2 2.8 × 10 1 0.0511.7562.09628
0.20 1.0 × 10 3 3.5 × 10 2 0.1020.8142.108142
0.30000.1330.6151.879200
0.40000.0660.1720.474200
0.50000.2320.3420.615200
robot30.60000.3660.4600.662200
0.70000.6400.7650.933200
0.80001.1481.3511.717200
0.90 5.6 × 10 7 4.4 × 10 6 1.5911.8613.67434
10 8.0 × 10 4 2.3 × 10 2 0.8581.9202.11441
1.1 2.3 × 10 5 6.1 × 10 4 3.9 × 10 3 1.9982.0232.1190
Table 9. Influence of crossover factor on best DE algorithm with C R = 0.3, 5 DOF robot arm (robot1), 6 DOF robot arm (robot2), 7 DOF robot arm (robot3).
Table 9. Influence of crossover factor on best DE algorithm with C R = 0.3, 5 DOF robot arm (robot1), 6 DOF robot arm (robot2), 7 DOF robot arm (robot3).
NameErrorTimeSuc
RobotFMinMeanMaxMinMeanMaxSuc
0.10 4.2 × 10 3 1.9 × 10 1 0.1971.3734.15860
0.20 1.0 × 10 4 1.0 × 10 3 0.5291.5103.76863
0.30 4.7 × 10 7 3.0 × 10 6 1.0111.6001.70432
0.40 8.3 × 10 7 1.1 × 10 5 1.0151.5971.6655
0.5 1.7 × 10 7 1.6 × 10 6 3.8 × 10 5 1.6121.6361.6870
robot10.6 3.1 × 10 7 3.2 × 10 6 6.6 × 10 5 1.5911.6291.9830
0.7 5.4 × 10 7 6.0 × 10 6 2.5 × 10 5 1.6181.6351.6910
0.8 9.6 × 10 7 9.0 × 10 6 1.7 × 10 4 1.6021.6191.6770
0.9 9.4 × 10 7 1.8 × 10 5 5.2 × 10 4 1.5921.6091.6740
1 3.8 × 10 6 2.9 × 10 5 3.3 × 10 4 1.5941.6281.9300
1.1 9.3 × 10 6 5.4 × 10 5 8.9 × 10 4 1.5901.6161.6910
0.10 4.0 × 10 4 1.1 × 10 2 0.6861.7221.91328
0.2 7.9 × 10 7 6.4 × 10 5 3.6 × 10 6 1.7481.7651.9050
0.3 2.3 × 10 6 2.4 × 10 4 6.4 × 10 5 1.7401.7621.9120
0.4 7.8 × 10 6 1.4 × 10 4 4.8 × 10 4 1.6911.7151.8060
0.5 1.1 × 10 5 3.4 × 10 4 1.41.7651.7811.8510
robot20.6 2.0 × 10 4 4.6 × 10 3 1.7 × 10 2 1.6921.7121.7860
0.7 6.0 × 10 4 7.9 × 10 3 4.8 × 10 2 1.7011.7211.8320
0.8 2.0 × 10 4 1.3 × 10 2 7.0 × 10 2 1.7181.7471.8460
0.9 1.9 × 10 3 2.4 × 10 2 8.3 × 10 2 1.7251.7471.8180
1 1.7 × 10 3 2.0 × 10 2 8.8 × 10 2 1.7211.7381.8240
1.1 6.0 × 10 4 1.8 × 10 2 8.8 × 10 2 1.7211.7421.8230
0.10 9.0 × 10 4 2.3 × 10 2 0.4651.7922.04934
0.20 3.5 × 10 5 1.9 × 10 3 0.9431.88422
0.3 2.2 × 10 7 3.6 × 10 6 1.6 × 10 4 1.8701.8911.9780
0.4 2.7 × 10 7 7.6 × 10 6 4.6 × 10 4 1.8561.8741.9660
0.5 1.2 × 10 6 1.3 × 10 5 2.3 × 10 4 1.8801.9081.9870
robot30.6 1.8 × 10 6 3.6 × 10 5 2.4 × 10 3 1.8611.8811.9460
0.7 1.3 × 10 5 1.9 × 10 4 5.4 × 10 3 1.8751.8962.0260
0.8 1.0 × 10 4 1.6 × 10 3 1.9 × 10 2 1.8541.8781.9380
0.9 2.0 × 10 4 3.8 × 10 3 1.5 × 10 2 1.8491.8761.9580
1 7.0 × 10 4 7.4 × 10 3 5.3 × 10 2 1.8621.8861.9950
1.1 1.5 × 10 3 1.1 × 10 2 4.3 × 10 2 1.8431.8661.9880
Table 10. Influence of crossover factor on best DE algorithm with C R = 0.6, 5 DOF robot arm (robot1), 6 DOF robot arm (robot2), 7 DOF robot arm (robot3).
Table 10. Influence of crossover factor on best DE algorithm with C R = 0.6, 5 DOF robot arm (robot1), 6 DOF robot arm (robot2), 7 DOF robot arm (robot3).
NameErrorTimeSuc
RobotFMinMeanMaxMinMeanMaxSuc
0.10 1.6 × 10 2 2.5 × 10 1 0.0801.3011.64540
0.20 1.0 × 10 3 2.5 × 10 2 0.1300.8361.644129
0.30000.1920.4761.336200
0.40000.3610.5641.259200
0.50000.5350.7901.245200
robot10.60 2.0 × 10 9 2.8 × 10 7 0.7521.2241.667198
0.70 3.4 × 10 7 3.6 × 10 6 1.2911.6392.53118
0.80 2.0 × 10 6 2.3 × 10 5 1.5951.6201.7271
0.9 7.5 × 10 7 8.1 × 10 6 7.4 × 10 5 1.5991.6602.8870
1 3.0 × 10 6 2.9 × 10 5 9.7 × 10 4 1.6241.6511.7180
1.1 1.1 × 10 5 8.1 × 10 5 9.8 × 10 4 1.6181.6451.7710
0.10 3.0 × 10 3 2.8 × 10 1 0.1050.9141.823117
0.20 8.0 × 10 4 4.0 × 10 2 0.3711.3381.973124
0.30 3.2 × 10 5 2.1 × 10 3 0.7931.6301.90874
0.40 6.2 × 10 7 7.9 × 10 5 0.8851.5693.325154
0.50 1.5 × 10 6 1.8 × 10 4 1.2601.7681.92424
robot20.6 7.0 × 10 7 6.7 × 10 6 3.1 × 10 4 1.7671.8132.2740
0.7 2.8 × 10 6 4.9 × 10 5 2.2 × 10 4 1.7441.7741.8410
0.8 4.3 × 10 5 7.1 × 10 4 3.8 × 10 3 1.7631.8202.4370
0.9 6.1 × 10 4 4.6 × 10 5 4.5 × 10 2 1.8211.9803.1880
1 2.5 × 10 3 2.4 × 10 2 8.0 × 10 2 1.8231.8932.5890
1.1 5.2 × 10 3 3.2 × 10 2 1.1 × 10 1 1.8521.9302.9320
0.10 9.0 × 10 4 4.0 × 10 2 0.1211.2953.02888
0.20 3.7 × 10 3 1.5 × 10 1 0.2311.4662.555112
0.30 1.2 × 10 5 8.7 × 10 4 0.5971.6143.000139
0.40 5.0 × 10 8 2.1 × 10 6 0.7931.6032.739180
0.50 5.0 × 10 7 2.2 × 10 5 1.1682.0693.11421
robot30.60 2.2 × 10 6 1.7 × 10 4 1.8602.1513.6761
0.7 1.3 × 10 6 9.6 × 10 6 3.31.9532.0392.7650
0.8 4.2 × 10 6 4.0 × 10 5 1.9 × 10 4 1.9672.1063.3450
0.9 1.0 × 10 4 4.0 × 10 4 6.5 × 10 3 1.9752.0622.9200
1 1.0 × 10 4 4.5 × 10 3 1.5 × 10 2 1.9742.0492.7770
1.1 9.0 × 10 4 1.1 × 10 2 3.4 × 10 2 1.9992.1264.1490
Table 11. The influence of crossover probability on the best DE algorithm when F = 0.4 , 5 DOF robot arm (robot1), 6 DOF robot arm (robot2), and 7 DOF robot arm (robot3).
Table 11. The influence of crossover probability on the best DE algorithm when F = 0.4 , 5 DOF robot arm (robot1), 6 DOF robot arm (robot2), and 7 DOF robot arm (robot3).
NameErrorTimeSuc
RobotDEMinMeanMaxMinMeanMaxSuc
0.1 1.7 × 10 7 8.1 × 10 6 1.4 × 10 4 1.5731.5951.6540
0.2 2.5 × 10 7 2.1 × 10 6 4.1 × 10 5 1.5921.6171.6680
0.30 8.8 × 10 7 2.2 × 10 5 0.8871.6141.6734
0.40 2.2 × 10 7 1.8 × 10 6 0.7621.5261.66761
0.50 3.0 × 10 9 6.0 × 10 7 0.5471.0481.660199
robot10.60000.3290.5491.066200
0.70000.2070.3330.683200
0.80000.1370.2150.469200
0.90000.1370.2150.469200
10 1.2 × 10 2 1.7 × 10 1 0.0621.3041.64440
0.1 4.0 × 10 4 1.0 × 10 3 5.6 × 10 2 1.7331.7632.4800
0.2 2.6 × 10 4 5.0 × 10 3 3.21.7331.7632.4800
0.3 1.0 × 10 5 4.4 × 10 3 3.0 × 10 2 1.7371.7651.8190
0.4 1.2 × 10 6 1.0 × 10 5 4.61.7151.7431.7960
0.5 1.6 × 10 7 1.1 × 10 5 1.31.7261.7461.8200
robot20.60 5.7 × 10 7 5.8 × 10 5 0.8591.4251.774169
0.70 3.6 × 10 7 2.5 × 10 5 0.4090.8651.788192
0.80 6.1 × 10 8 1.2 × 10 5 0.2530.6831.774199
0.90 4.2 × 10 7 8.4 × 10 5 0.1660.5181.751199
10 7.7 × 10 3 8.4 × 10 2 0.0081.3981.81447
0.1 1.0 × 10 4 4.0 × 10 3 2.3 × 10 2 1.9001.9291.9980
0.2 3.5 × 10 6 1.4 × 10 4 1.5 × 10 2 1.8911.9181.9770
0.3 6.8 × 10 7 9.8 × 10 6 1.0 × 10 3 1.8701.9051.9660
0.4 2.0 × 10 7 2.7 × 10 6 1.0 × 10 4 1.9001.9241.9900
0.50 1.1 × 10 6 1.01.5361.9051.9737
robot30.60 8.5 × 10 8 1.4 × 10 5 0.8101.4151.965188
0.70 1.0 × 10 8 2.1 × 10 6 0.4490.7531.986199
0.80000.3200.5951.601200
0.90000.2000.4981.765200
10 1.0 × 10 2 1.4 × 10 1 0.0891.4841.97455
Table 12. The influence of population size on the best DE algorithm with F = 0.4 , C R = 0.8 . Total error and time for the mobile manipulator robot with 5 DOF arm (robot1), 6 DOF arm (robot2), and 7 DOF arm (robot3).
Table 12. The influence of population size on the best DE algorithm with F = 0.4 , C R = 0.8 . Total error and time for the mobile manipulator robot with 5 DOF arm (robot1), 6 DOF arm (robot2), and 7 DOF arm (robot3).
NameErrorTimeSuc
RobotNPMinMeanMaxMinMeanMaxSuc
200 6.0 × 10 4 2.1 × 10 2 0.0480.2540.655183
250 1.1 × 10 8 2.2 × 10 6 0.0620.2550.810199
300000.0730.2250.553200
350000.0740.2090.776200
400000.0880.2000.573200
robot1450000.0900.1750.589200
500000.1040.1850.469200
550000.1020.1580.409200
600000.1020.1630.282200
650000.1270.1720.363200
700000.1350.1750.319200
200000.0550.2140.631200
250000.0800.2810.867200
300000.0810.3020.957200
350 8.0 × 10 9 1.6 × 10 6 0.1320.4231.258199
400 4.9 × 10 8 9.8 × 10 6 0.1470.4721.392199
robot2450000.1680.5101.330200
500000.2070.5701.659200
550000.2010.5091.705200
600000.1930.4681.215200
650000.2110.4971.510200
700000.2120.4361.840200
200 1.3 × 10 3 8.4 × 10 2 0.0600.3010.799186
250 3.0 × 10 4 6.1 × 10 2 0.1090.4210.981194
300 1.9 × 10 8 3.3 × 10 6 0.1460.4911.167197
350 2.6 × 10 8 5.2 × 10 6 0.1570.5741.392199
400000.1580.5571.513200
robot3450000.1860.5281.586200
500000.1970.5801.859200
550000.1970.5091.429200
600000.2040.4641.438200
650000.2130.4160.929200
700000.2400.4131.093200
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

Li, M.; Qiao, L. A Review and Comparative Study of Differential Evolution Algorithms in Solving Inverse Kinematics of Mobile Manipulator. Symmetry 2023, 15, 1080. https://doi.org/10.3390/sym15051080

AMA Style

Li M, Qiao L. A Review and Comparative Study of Differential Evolution Algorithms in Solving Inverse Kinematics of Mobile Manipulator. Symmetry. 2023; 15(5):1080. https://doi.org/10.3390/sym15051080

Chicago/Turabian Style

Li, Minghao, and Lijun Qiao. 2023. "A Review and Comparative Study of Differential Evolution Algorithms in Solving Inverse Kinematics of Mobile Manipulator" Symmetry 15, no. 5: 1080. https://doi.org/10.3390/sym15051080

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