Next Article in Journal
The Friction of Radially Loaded Hybrid Spindle Bearings under High Speeds
Previous Article in Journal
The Neutral Voltage Difference Signal as a Means of Investigating Eccentricity and Demagnetization Faults in an AFPM Synchronous Generator
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Inverse Kinematics of Robot Manipulator Based on BODE-CS Algorithm

1
School of Mechanical Engineering, Beijing Institute of Technology, Beijing 100081, China
2
School of Computer Science and Technology, Beijing Institute of Technology, Beijing 100081, China
3
School of Mechatronical Engineering, Beijing Institute of Technology, Beijing 100081, China
*
Author to whom correspondence should be addressed.
Machines 2023, 11(6), 648; https://doi.org/10.3390/machines11060648
Submission received: 25 February 2023 / Revised: 1 June 2023 / Accepted: 9 June 2023 / Published: 14 June 2023
(This article belongs to the Section Robotics, Mechatronics and Intelligent Machines)

Abstract

:
Differential evolution is a popular algorithm for solving global optimization problems. When tested, it has reportedly outperformed both robotic problems and benchmarks. However, it may have issues with local optima or premature convergence. In this paper, we present a novel BODE-CS (Bidirectional Opposite Differential Evolution–Cuckoo Search) algorithm to solve the inverse kinematics problem of a six-DOF EOD (Explosive Ordnance Disposal) robot manipulator. The hybrid algorithm was based on the differential evolution algorithm and Cuckoo Search algorithm. To avoid any local optimum and accelerate the convergence of the swarm, various strategies were introduced. Firstly, a forward-kinematics model was established, and the objective function was formulated according to the structural characteristics of the robot manipulator. Secondly, a Halton sequence and an opposite search strategy were used to initialize the individuals in the swarm. Thirdly, the optimization algorithms applied to the swarm were dynamically allocated to the Differential Evolution algorithm or the Cuckoo algorithm. Fourthly, a composite differential algorithm, which consisted of a dynamically opposite differential strategy, a bidirectional search strategy, and two other typically used differential strategies were introduced to maintain the diversity of the swarm. Finally, two adaptive parameters were introduced to optimize the amplification factor F and cross-over probability Cr. To verify the performance of the BODE-CS algorithm, two different tasks were tested. The experimental results of the simulation showed that the BODE-CS algorithm had high accuracy and a fast convergence rate, which met the requirements of an inverse solution for the manipulator.

1. Introduction

Robotics have integrated many achievements in theoretical knowledge and technology, including controls [1], artificial intelligence [2], and complex mechanisms [3], etc. To solve the problem of path planning, motion control, and trajectory tracking, among others, a kinematic analysis is necessary. It includes forward and inverse kinematics, where forward kinematics [4] describe the process of obtaining the end-effector’s position and orientation by using the relative configurations of each pair of adjacent links, and inverse kinematics describe the process of obtaining a set of joint variables based on the desired position and orientation. The inverse kinematics of the manipulator play an important role in robotic research.The desired trajectory can be transformed via inverse kinematics into the corresponding joint trajectories [5]. It is also the fundamental technology for solving many problems, such as trajectory tracking [6], object grasping [7], and dynamic analysis [8]. It allows for the joint variables associated with the required task to be determined. The IK (inverse kinematics) problem is a complex coupling problem. Many methods have been proposed that can be divided into three categories: analytical solutions (closed-form solutions) [9], numerical solutions [10], and intelligent algorithms [11]. Regarding the analytical solutions, they consist of algebraic and geometric aspects [12]. For example, Gan et al. [13] proposed a complete analytical solution for the inverse kinematics of a P2Arm robotic arm. The method provided the robot arm access to any position in an undefined environment. However, traditional closed-form methods are difficult to implement in robots with particular geometric features. The joint variables of numerical solutions are obtained for iterative computational procedures. This has been the main approach for resolving the IK problem of complex articulated manipulators. Unfortunately, traditional numerical methods, such as pseudo-inverse methods [14], the Newton method [15], and so forth, are time-consuming [16]. The Jacobian IK method, with its complex matrix calculations and singularity issues, has made the problem difficult to solve. Similar to the Jacobian IK method, the iteration of the Newton method is complex and difficult to implement. Due to the problems with the Jacobian and Newton methods, various intelligent algorithms have been proposed, such as the GA (Genetic Algorithm) [17,18], PSO (Particle Swarm Optimization) [19], DE (Differential Evolution) [20], NN (Neural Networks) [21], ABC (Artificial Bee Colony) [22], and ACS (Ant Colony System) [23]. The main idea involved in using intelligent algorithms for solving inverse kinematics is to transform the problem into minimizing or maximizing a fitness function with an iterative strategy. The comparison of the algorithms is shown as Table 1.
The Differential Evolution (DE) algorithm is an intelligent optimization algorithm, which was proposed by Price and Storn [31]. It has many appealing characteristics, such as fast convergence, few control parameters, and excellent robustness. It has commonly been used to optimize engineering problems, such as signal processing [32], satellite image enhancement [33], and numerical optimization [34]. In the robotic area, DE algorithms and their variants have been widely used in motion planning [35], path trajectory [36], visual control [37], and so on. A novel DE algorithm was proposed by Ren et al. [38] to plan a minimum-acceleration trajectory for a humanoid robot. The results indicated that the improved DE algorithm was effective in generating the minimum-acceleration trajectory for the humanoid robot with a seven-DOF manipulator. Zhang et al. [39] proposed a multi-objective algorithm that hybridized the DE algorithm with a PSO. The path length, the degree of safety, and the degree of smoothness were taken as the objectives to optimize. The experiment results revealed that the hybrid algorithm outperformed other algorithms on the path length, the degree of safety, and the degree of smoothness. Cuckoo Search (CS) is a novel search algorithm proposed by Yang and Deb. It is a widely used algorithm that has less computational demand, and it can be easily merged into other algorithms. Due to its simplistic mathematical process, it has been used in multi-objective optimization [40], neural networks [41], facial recognition [42], and so on. Similar to the DE algorithm, the CS has also been widely used in robotics for such applications as trajectory tracking [43], path planning [44], and so forth. Sharm et al. [45] used a tournament selection function, which considered both path time and length, to optimize the CS algorithm for robot path planning. Compared to the PSO and the traditional CS, the performance of Sharm’s improved CS algorithm was better in terms of path length and time optimization. To obtain a higher efficiency and an automated trajectory, the Adaptive Cuckoo Search (ACS) was proposed by Zhang et al. [46] In the algorithm, the path time was minimized under strict dynamic constraints. Compared to other algorithms, the ACS algorithm had better performance, with a better convergence speed and greater efficiency. Karahan et al. [47] presented a novel trajectory generation method that considered time optimization, jerk optimization, and time–jerk optimization. The improved CS was proposed and compared to earlier studies, and the results showed that the improved CS was more effective than other algorithms. Despite the significant advantages of the DE and CS algorithms, they are easily influenced by local optima with low convergence accuracy. Although many variants of the DE algorithm have been proposed, a single-mutation strategy has often been unable to solve complex optimization problems; it is also difficult for the basic DE algorithm to balance the global exploration ability and local development ability. Meanwhile, they usually focused on optimizing the cross-over probabilities and mutation factors. The quality of the initial swarm and the weight coefficient in the fitness function has a significant influence on the results, which is typically ignored. Additionally, if the swarm size is small, the risk of premature convergence with a DE algorithm increases. To solve the problems and improve the accuracy and performance of DE algorithms, we proposed a novel hybrid algorithm: the Bidirectional Opposite Differential Evolution–Cuckoo Search (BODE-CS) algorithm. The contributions of this study are summarized in the following:
(1)
A novel objective function was formulated according to the structural characteristics of the robot manipulator. By using the D–H (Denavit–Hartenberg) method, the pose matrix of the robot end effector was analyzed. Then, a novel objective function was proposed to accelerate the algorithm’s convergence rate. The objective function considered both the position error and orientation error. The coefficient of the orientation error was associated with link length, link twist angle, link offset, and joint angle, etc.
(2)
A Halton sequence and the opposite strategy were used to initialize the swarm. A Halton sequence with a low difference was proposed to initialize the swarm instead of the random initialization method. The Halton sequence could improve the diversity of the swarm and enable the individuals to be more evenly distributed. Meanwhile, the opposite strategy was also applied to optimize the swarm quality.
(3)
A multi-strategy composite DE algorithm with improved factors was formulated. To avoid the local optimum, firstly, a dynamical opposite differential evolution algorithm and bidirectional search strategies were introduced. Since the maximum and minimum values of each dimension were dynamically changed during the iterative process, a smaller search range was more conducive to algorithm convergence. Therefore, the maximum and minimum values of each dimension were selected as new boundaries for generating new individuals. Then, by adjusting the differential evolution formula symbols, new bidirectional individuals could be generated. Based on the proposed two strategies, two typical DE mutation strategies were also introduced to form and enhance a new multi-strategy composite DE algorithm. Finally, the amplification factor (F) in mutation and the cross-over probability factor ( C r ) were both improved.
(4)
A multi-strategy CS algorithm was constructed. During the CS algorithm’s operation, the dynamically opposite strategy, linear global best strategy, improved step strategy, and linear decreasing abandonment strategy were applied. The linear global best strategy considered both the current individual and the global best individual. A weighted method was used to combine them in order to accelerate the swarm convergence. An improved step strategy was used to increase the diversity of the swarm, and the linear decreasing abandonment strategy could improve the diversity at the beginning of searching, as well as increased probability to retain the best individual at the end of searching.
(5)
The mechanism for selecting the best algorithm and strategy was established for the BODE-CS algorithm. First, the BODE algorithm and improved CS algorithm were dynamically selected by an algorithm selection function. Then, a piece-wise function was formulated to choose one strategy for the BODE algorithm and optimize the swarm. Meanwhile, the dynamically opposite strategy and the best linear global strategy were also applied to improve the CS algorithm.
The remainder of this paper is organized as follows: In Section 2, the kinematic model of our robot’s end effector is established, and a novel objective function is formulated. Then, in Section 3, the procedures of the traditional DE algorithm and CS algorithm are introduced. Additionally, the improved strategies for DE and CS are also introduced to accelerate convergence and mitigate the influence of the local optima. In Section 4, the simulations are described, and the comparative results of the BODE-CS algorithm are presented. Finally, the conclusion and perspectives are provided in Section 5.

2. Kinematic Analysis for the Robot Manipulator

2.1. Mathematical Model of the Manipulator

Each joint is associated with a joint variable q. The expression of variable q is as follows:
q = [ q 1 q 2 q n ] T ,
where q i represents the i t h joint variable; in the case of a revolute joint, the variable q i is the angle ofrotation, and, in the case of a prismatic joint, it is the joint displacement [48]. n represents the number of DOFs.
The homogeneous transformation matrix is used to describe the position and orientation of one coordinate system in another coordinate system. It is used to change the reference frame in which a vector or frame is represented [49]. The superscript of the matrix indicates the reference coordinate system; the subscript right corner of the matrix identifies the target coordinate system. It includes a translation matrix P 3 × 1 , a rotation matrix R 3 × 3 , and a 1 × 4 matrix (0, 0, 0, 1). According to the D–H method, the homogeneous transformation matrix A i i 1 could be obtained through the following:
A i i 1 = R o t z , θ i T r a n s z , d i T r a n s x , a i R o t x , α i = c θ i s θ i 0 0 s θ i c θ i 0 0 0 0 1 0 0 0 0 1 1 0 0 0 0 1 0 0 0 0 1 d i 0 0 0 1 1 0 0 a i 0 1 0 0 0 0 1 0 0 0 0 1 1 0 0 0 0 c α i s α i 0 0 s α i c α i 0 0 0 0 1 = c θ i s θ i c α i s θ i s α i a i c θ i s θ i c θ i c α i c θ i s α i a i s θ i 0 s α i c α i d i 0 0 0 1
where i is the link number, and A i i 1 represents the homogeneous transformation matrix relating the description of a point in Frame i ( O i X i Z i ) to the description of the same point in Frame (i-1) ( O i 1 X i 1 Z i 1 ). The parameters a i , α i , d i , and θ i represent link length, link twist angle, link offset, and joint angle, respectively.
Thus, with respect to a reference to the base Frame O b x b y b z b , the kinematics function from the end-effector Frame O e x e y e z e to the base Frame is calculated as follows:
T e b ( q ) = i = 1 n A i i 1 = n e b ( q ) s e b ( q ) a e b ( q ) p e b ( q ) 0 0 0 1 = n x s x a x p x n y s y a y p y n z s z a z p z 0 0 0 1 = R e b P e b 0 1 × 3 1
where T e b ( q ) represents the pose matrix from the end-effector coordinate system to the base coordinate system, n e b ( q ) , s e b ( q ) , and a e b ( q ) represent the unit vectors of a frame attached to the end-effector, p e b ( q ) represents the position vector from the end-effector coordinate system to the base coordinate system, R e b represents the orientation matrix from the end-effector coordinate system to the base coordinate system, and P e b represents the position vector from the end-effector coordinate system to the base coordinate system.

2.2. Establishment of the Objective Function

In this study, we used a weighting method to formulate the fitness function. The IK problem of the robot manipulator aimed to optimize the errors between the desired pose and the estimated pose. The desired pose matrix T e b is given before solving the IK problem. The estimated pose matrix T ^ e b is obtained by substituting the current joint variable q into the formula.
T e b = R e b P e b 0 1
T ^ e b = R ^ e b P ^ e b 0 1
where T e b , T ^ e b R 4 × 4 , and R e b , P e b represent the desired orientation (posture) vector and position vector, respectively, and R ^ e b and P ^ e b represent the estimated orientation vector and position vector, respectively. R ^ e b and P ^ e b are the current rotation matrix and position matrix, respectively.
The pose errors consist of the orientation error Δ R and the position error Δ P . Many earlier scholars have assigned the coefficients of Δ R and Δ P according to their experience or through a significant amount of calculation. However, the process can be time intensive, and the results lack theoretical guidance and controllable parameters. The position and posture of the robot end effector is determined by the D–H parameters. Therefore, based on the D–H parameters, we proposed a new method to calculate the coefficients of Δ R and Δ P to define a novel fitness function in the end. Then, a novel fitness function is proposed as follows:
f = ω P Δ P + ω R Δ R
n e r r = ( n x n ^ x ) 2 + ( n y n ^ y ) 2 + ( n z n ^ z ) 2 s e r r = ( s x s ^ x ) 2 + ( s y s ^ y ) 2 + ( s z s ^ z ) 2 a e r r = ( a x a ^ x ) 2 + ( a y a ^ y ) 2 + ( a z a ^ z ) 2 Δ R = n e r r + s e r r + a e r r Δ P = ( p x p ^ x ) 2 + ( p y p ^ y ) 2 + ( p z p ^ z ) 2
ω p = 1
l a r m = i = 1 n ( | d i | + | a i | )
λ p = p o s max p o s min l a r m
λ p + λ R = 1
ω R = λ R · c r a d i = 1 n ( θ i m a x θ i m i n ) λ p
where p o s max and p o s min are the maximum distance and minimum distance from the end-effector position to the origin of the base coordinate position, respectively; l a r m represents the sum of all link lengths | a i | and link offsets | d i | of the manipulator; and θ i m a x and θ i m i n are the i t h dimension upper and lower boundaries, respectively. The parameter c r a d was equal to 1 rad, and it was used to adjust the unit of ω R . The convergence precision of the orientation and position errors is different. In order to balance the difference between orientation and position errors, we proposed a novel weighted method. Meanwhile, due to the end-effector’s position being affected by D–H parameters (link length, link offset, and joint angle, etc.), we associate the position error Δ P of the end effector with the link length and link offset, and we associate the orientation error Δ R with joint angle (Formula (12)). We calculate the workspace of the robot manipulator using the Monte Carlo method and obtain the maximum distance pos max and minimum distance pos min of the robot’s end effector. The process of calculating ω R is as follows: Firstly, ω P is assigned to 1, and the parameter l arm is calculated by considering the absolute value of link length a i and link offset d i with Formula (9). Secondly, calculate the parameter λ p by considering the pos max ,   pos min   and   l arm (Formula (10)). Thirdly, calculate the parameter λ R using Formula (11). Finally, calculate the parameter ω R using Formula (12).

3. Hybrid BODE-CS Algorithm

3.1. Standard DE Algorithm

DE is a random heuristic algorithm, which works in two stages: initialization and evolution. The process of initialization usually generates the individuals randomly, and, in the second stage, the individuals usually go through mutation, crossover, and processing. The process of DE is detailed as follows:
(a)
Initialization
To begin, each individual in the swarm is generated randomly. If the swarm consists of N individuals, and each individual has a D dimension, the population initialization process would be the following:
x j k = x k , min + ( x k , max x k , min ) · rand ( 0 , 1 )
where x k , max and x k , min are the upper and lower boundaries of the variable j, respectively, and rand(0, 1) is a random uniform distribution number in (0, 1). The variable j represents the j th individual in the swarm, and k represents the k th component of the x j individual.
(b)
Mutation
In this procedure, new individuals are generated by introducing the differential vector. The basic mutation process is calculated as the following:
v j k ( t + 1 ) = x r 1 k ( t ) + F · ( x r 2 k ( t ) x r 3 k ( t ) )
where F [ 0 , 2 ] is the scale factor, and the indices r 1 , r 2 , r 3   { 1 , 2 , 3 , , N } , and ( r 1 r 2 r 3 ) have random values from 1 to N; t and t + 1 represent t th and ( t + 1 ) th iterations, respectively. Many variant DE algorithms have been proposed, and the most common DE variants are the following:
(1)
DE/rand/1:
v j k ( t + 1 ) = x r 1 k ( t ) + F · ( x r 2 k ( t ) x r 3 k ( t ) )
(2)
DE/best/1:
v j k ( t + 1 ) = x best k ( t ) + F · ( x r 2 k ( t ) x r 1 k ( t ) )
(3)
DE/best/2:
v j k ( t + 1 ) = x best k ( t ) + F · ( x r 1 k ( t ) x r 2 k ( t ) ) + λ · ( x r 3 k ( t ) x r 4 k ( t ) )
(4)
DE/rand/2:
v j k ( t + 1 ) = x r 1 k ( t ) + F · ( x r 2 k ( t ) x r 3 k ( t ) ) + λ · ( x r 4 k ( t ) x r 5 k ( t ) )
(5)
DE/current-best/1:
v j k ( t + 1 ) = x j k ( t ) + F · ( x best k ( t ) x j k ( t ) ) + λ · ( x r 1 k ( t ) x r 2 k ( t ) )
The indices r 1 , r 2 , r 3 , r 4 , and r 5 { 1 , 2 , 3 , , N } represent the index of five random individuals in the swarm, and r 1 r 2 r 3 r 4 r 5 ; x best k ( t ) and x j k ( t ) represent the best individual and current individual in the swarm, respectively; and F and λ are the scale factors. With the development of the DE algorithm, various DE variants have been proposed as well, such as ODE [50], CODE [51], MADE [52], JDE [53], NSDE [54], JADE [55], SDE [56], and so forth.
(c)
Crossover
In the crossover operation, u j k ( t + 1 ) is generated based on the following
u j k ( t + 1 ) = v j k ( t + 1 ) if rand ( 0 , 1 ) < C r or ( k = k rand ) x j k ( t ) otherwise ,
where u j k ( t + 1 ) represents the new individual established by the crossover process, and it is the k th component of vector u j ( t + 1 ) ; v j k ( t + 1 ) represents the new individual generated by the mutation, and it is the k th component of vector v j ( t + 1 ) ; x j k ( t ) represents the original individual in the parent group, and it is the k th component of vector x j ( t ) ; C r ( 0 , 1 ) represents the cross-over rate; and k rand is a random number, and, in k rand ( 1 , 2 , , D ) , D is the problem dimensionality.
(d)
Selection
The selection procedure determines which candidate solution ( u j k or x j k ) survives to the next generation. The operation is described as follows:
x j k ( t + 1 ) = u j k ( t + 1 ) if fitness ( u j k ( t + 1 ) ) < fitness ( x j k ( t ) ) x j k ( t ) otherwise ,
where fitness ( u j k ( t + 1 ) ) represents the fitness value of u j k ( t + 1 ) , and fitness ( x j k ( t ) ) represents the fitness value of x j k ( t ) .

3.2. Improved Strategy for Differential Evolution Algorithm

The traditional DE algorithm usually generates the individuals randomly; however, the individuals then have a non-uniform distribution, and the convergence rate of the algorithm is usually unstable. Therefore, we introduced a Halton sequence strategy to generate a uniform distribution of individuals and improve the convergence rate of the swarm. Then, the bidirectional search strategy and dynamical opposite DE were introduced into the DE/best–best/1 algorithm to obtain high-quality individuals. We also combined the two proposed strategies, DE/rand–best/1 and DE/rand–best/1, to form a composite DE algorithm; the selection of the five equations was determined by an adaptive piece-wise function.

3.2.1. The Halton Sequence Strategy for the DE Algorithm

In this section, a Halton sequence strategy [57] was used to initialize the swarm of the BODE-CS algorithm. This is a popular multi-dimensional low-discrepancy sequence. The sequence was generated based on a deterministic method, and several co-prime numbers were used to discretize its search space. The D-dimensional Halton sequence is expressed as follows:
H D ( n ) = { φ b 1 ( n ) , φ b 2 ( n ) , , φ bD ( n ) } , n = 1 , 2 , 3 , , N ,
where b j is a prime number, and φ bj ( n ) is the j th radical inverse function of the following:
φ b j ( n ) = i = 1 n ahal i · b j i 1 , 0 ahal i b j 1 .
Therefore, the initialization could be expressed as follows:
v j k = x k , min + ( x k , max x k , min ) · H D ( j ) ,
where H D ( j ) is the Halton sequence of the j th individual.

3.2.2. A Bidirectional Search Strategy for the DE Algorithm

The bidirectional search is a strategy that uses the best solution as the base vector. The solution and search process included two opposite directions. The operations are described as Formulas (21) and (22).
v j k ( t + 1 ) = x best k ( t ) + F · ( x r 1 k ( t ) x r 2 k ( t ) ) + λ · ( x best k ( t ) x r 3 k ( t ) )
v j k ( t + 1 ) = x best k ( t ) F · ( x r 1 k ( t ) x r 2 k ( t ) ) λ · ( x best k ( t ) x r 3 k ( t ) )
F = ( F max F min ) · ( 2 e ( t T max ln ( 2 ) ) ) ,
where F and λ are adaptive scale factors for the two differential vectors, respectively. F max , F min , and λ are constants in the formulas. T max represents the maximum iteration number.
To enhance the explosive ability of the improved algorithm, an adaptive cross-over probability C r was used in this study; the expression is the following:
C r = C min + ( C max C min ) · ( t T max ) ,
where C max and C min are constants.

3.2.3. An Improved Opposite Strategy on the DE Algorithm

The ODE is an opposition-based method. It enhances the search process by generating the opposite points of initial individuals. By utilizing this method, the diversity of the swarm could be improved. In this study, we used traditional and contraction ODE methods to initialize the swarm and produce new solutions, respectively, during the iteration process. The dynamic contraction ODE increased the possibility of finding a better position and assisted in fine-tuning the evolution of the algorithm.
(a) 
Opposition-Based swarm initialization
The initial individuals were calculated by the following:
v j k ( t + 1 ) = x k , max + x k , min x j k ( t ) .
After the opposition-based method was executed, the fitness values of the initial individual and the opposition-based individuals were calculated. Then, we selected the individuals with lower fitness values as the next generation.
(b) 
Contraction-Opposition-Based swarm optimization
As compared to the process of swarm initialization, during the iterative process, the maximum and minimum values of each dimension in the current swarm were dynamically changed. To fine-tune and generate new individuals, we used the maximum and minimum of each swarm dimension, instead of the initial upper boundary and lower boundary, to optimize the swarm.
v j k ( t + 1 ) = S k , max ( t ) + S k , min ( t ) ( 1 C csor C rand ) x j k ( t )
where S k , max , S k , min represent the maximum and minimum values of each dimension in the swarm, respectively—during the search process, the boundary ( S k , min , S k , max ) becomes increasingly smaller than the predefined boundary ( x min , x max ); C csor is a constant; C rand is a random number between 0 and 1; and the C csor and C rand form an adaptive coefficient for the ODE formula. The two factors in the Formula (26) promoted the adaptive change in the current individual.

3.2.4. The Procedure of the BODE Algorithm

In this section, we proposed a novel composite strategy to optimize the robot manipulator problem. The BODE algorithm consisted of five variant algorithms and a piece-wise function, which were utilized to enable the BODE algorithm to randomly select the mutation operations. The piece-wise function and specific mutation operations are defined as follows:
r base 1 = 0.9 0.2 · ( t T max ) 2 r base 2 = 0.65 0.2 · ( t T max ) 2 r co 1 = r base 2 + ( r base 1 r base 2 ) 3 r co 2 = r base 2 + 5 ( r base 1 r base 2 ) 6
v j k ( t + 1 ) = x best k ( t ) + F · ( x r 1 k ( t ) x r 2 k ( t ) ) + λ · ( x best k ( t ) x r 3 k ( t ) ) , if r DE > r base 1 v j k ( t + 1 ) = S j , max ( t ) + S j , min ( t ) ( 1 C csor · C rand ) x j k ( t ) , if r co 2 < r DE r base 1 v j k ( t + 1 ) = x j k ( t ) + F · ( x r 1 k ( t ) x r 2 k ( t ) ) + λ · ( x best k ( t ) x r 3 k ( t ) ) , if r co 1 < r DE r co 2 v j k ( t + 1 ) = x best k ( t ) F · ( x r 1 k ( t ) x r 2 k ( t ) ) λ · ( x best k ( t ) x r 3 k ( t ) ) , if r base 2 < r DE r co 1 v j k ( t + 1 ) = x r 1 k ( t ) + F · ( x r 2 k ( t ) x r 3 k ( t ) ) + λ · ( x best k ( t ) x r 1 k ( t ) ) , if r DE r base 2
where r base 1 , r base 2 , r co 1 , and r co 2 are the parameters used to select the proper strategy in order to operate the mutation process of the BODE-CS algorithm, and C csor is a constant. The first equation in Formula (28) is DE/best-best/1, the second equation is based on the dynamical opposite strategy, the strategy of the third equation is DE/current-best/1, and the fourth equation and the first equation are mutated based on bidirectional strategy. The strategy of the last equation is DE/rand-best/1. The pseudo-code of the BODE algorithm is given in Algorithm 1.
Algorithm 1: The pseudo-code of the BODE algorithm. IK for robot manipulator based on BODE algorithm.
1:
f ← objective function defined in Formula (6)
2:
Initialization parameters
3:
for each individual j do
4:
Initialize individual position x j with Halton sequence strategy (Formulas (18)–(20))
5:
optimize the individuals by considering an opposite strategy with the following Formula (25)
6:
end
7:
Compare the fitness value of the individuals generated by the opposite strategy
8:
   with theinitial individual, respectively and update the individuals
9:
repeat
10:
for each individual j do
11:
   randomly select x r 1 k , x r 2 k and x r 3 k
12:
  randomly generate a number r DE and compare this with Formula (27)
13:
   select the proper DE strategy by using Formula (28) and compute a new mutant
14:
   vector v j k ( t + 1 )
15:
   calculate the adaptive crossover probability C r by using Formula (24)
16:
      and do crossover operation. Calculate a trial vector u j k using Formula (16)
17:
   select the individual with smaller fitness for the next generation using
18:
      Formula (17)
19:
until stop criteria or the T max is met.
The position x j ( q 1 , , q n ) represents the joint angle in each dimension, and r DE is a randomly generated number between 0 and 1.

3.3. Standard Cuckoo Search Algorithm

In the CS algorithm, there are three control parameters: the switch parameter, the scale factor, and the step size. The operation is calculated as follows:
  • Each cuckoo randomly selects one nest in which to lay an egg.
  • The nest with the best fitness value eggs is selected as the best nest and retained for the next generation.
  • The host bird may remove an alien egg with a probability ( P a ) or abandon it and build a new nest elsewhere.
Due to Lévy flight, the search speed of the CS algorithm could be improved efficiently. This provided a random walk, which led the search for a new environment; the step size used the Lévy distribution. The algorithm could efficiently balance the local search and global search. The local and global random walk formulas of Lévy flight were calculated and are defined as follows:
The local random walk:
x j k ( t + 1 ) = x j k ( t ) + α l s H ( P a ε ) ( x j k ( t ) x best k ( t ) ) .
The global random walk:
x j k ( t + 1 ) = x j k ( t ) + α g L ( s , λ c ) , j = 1 , 2 , , n
L ( s , λ c ) = λ c Γ ( λ c ) sin ( π λ c 2 ) π ( s ( 1 + λ c ) ) , ( 1 < λ 3 ) ,
where α l and α g represent positive step-size scaling factors; ε is a random number in (0,1); x j k ( t + 1 ) represents a new location; x j k ( t ) represents the current location; ⊗ represents the entry-wise multiplication of two vectors; H ( ) represents the Heaviside function; Γ ( ) represents the gamma function; x best k ( t ) is the best solution; s represents the step length; and L ( s , λ c ) represents the Lévy distribution.
In Mantegna’s algorithm [58], the step length s is computed by the following:
s = u m v m 1 β ,
where β is an index parameter that is usually defined as 3 2 , and u m and v m are calculated using the normal distribution method.
u m N ( 0 , σ um 2 ) , v m N ( 0 , σ vm 2 ) ,
where σ um and σ vm are defined as follows:
σ um = Γ ( 1 + β ) sin ( π β 2 ) Γ ( 1 + β ) 2 β 2 ( β 1 ) 2 1 β , σ vm = 1 .
The specific steps were the following:
(a) 
Initialization
The individuals were individualized, and all the parameters for the algorithm were set.
(b) 
Lévy flight
The individuals were updated according to the Formula (29) or Formula (30).
(c) 
Random walking
Nests were abandoned by considering P a , and new nests were generated according to the local random walk. In addition to the method mentioned in Formula (29), the method with two random individuals was also widely used. The formula is expressed by the following:
x j k ( t + 1 ) = x j k ( t ) + rand ( 0 , 1 ) · ( x rcs 1 k x rcs 2 k ) , rand ( 0 , 1 ) > P a x j k ( t ) , otherwise
where indices rcs 1 , rcs 2 { 1 , 2 , 3 , , N } represent the index of two random different individual in the swarm.

3.4. Improved Strategy for CS

3.4.1. An Opposite Strategy for the Swarm

The opposition-based strategy is an effective exploration enhanced method. In this section, we also used the dynamical ODE mentioned previously to enhance the explosive ability of the BODE-CS algorithm. In contrast to the ODE applied in the DE algorithm, when many strategies were applied, the time consumption increased. To reduce the calculation time and accelerate convergence, the parameter r cso was introduced to determine whether the ODE method applied to the CS. The r cso is expressed as follows:
r cso = C o ( 1 t T max ) ,
where T max represents the maximum iteration number, and C o is a constant.

3.4.2. A Linear Global Best Strategy for the Swarm

The linear global best strategy is used to generate new individual by considering current information and the best information in the swarm.
v j k ( t + 1 ) = ω j x j k ( t ) + ω gbest x gbest k ( t )
where ω j and ω gbest are the coefficients of the current vector and the global best vector, respectively. The two coefficients are constants. To balance the calculation time and the diversity of the swarm, we introduced a criterion to determine whether the linear global best strategy would be used or not; the criterion is as follows:
r csbi = C bi ( f it max f it ave f it max fit min )
where C bi is a constant, and fit max , fit ave , and fit min are the maximum fitness value, average fitness value, and minimum fitness value of the swarm, respectively.

3.4.3. An Improved Step Strategy and Linear Decreasing Abandonment Strategy for Random Walking

The scaling factor α s in the step size of the Lévy flight was fixed, because, if the α s were to be set too high, the convergence rate cannot be guaranteed. Therefore, we optimized the step size of the Lévy flight with a random coefficient:
s = α s × u m v m 1 β
α s = cos ( 2 π r css ) + 1 2
where r css is a random number between 0 and 1.
Meanwhile, due to the probability P a of abandonment, the better individual could be abandoned. Therefore, a P a with a linearly decreasing strategy and the new nest was generated after abandoning a biased/selective random walk strategy. The linearly decreasing P a is expressed as the following:
P a = P amax ( P amax P amin ) × t T max
where P amax and P amin represent the maximum probability of abandonment and the minimum probability of abandonment, respectively. Both the improved step strategy and the linearly decreasing abandonment strategy were used to improve the diversity of the swarm and the convergence rate.

3.5. The Procedure of Improved CS

As previously mentioned, four strategies were introduced into the CS algorithm, and, based on the strategies and the standard CS, we proposed a multi-strategy framework to maximize the performance of each individual. The details of the improved CS algorithm are shown in Algorithm 2.
Algorithm 2: The pseudo-code of improved CS. IK for robot manipulator based on an improved CS algorithm.
1:
f ← objective function defined in Formula (6).
2:
Initialization parameters and individuals.
3:
repeat
4:
   for each individual j do
5:
      Generate a new nest using Lévy flights method (Formulas (29), (33) and (34))
6:
      (Formulas (39) and (40)) evaluate its fitness value and update the nest
7:
      update the nest with a better fitness value
8:
   end
9:
      Abandon a fraction ( P a ) of the worst nests and build new nests via Lévy flights
10:
      (Formulas (35) and (41)) and find the best nest in the current swarm
11:
      keep the best nest with quality solution
12:
   for each individual j do
13:
      Generate a random number r a and compare it with r cso by using
14:
      Formula (36).
15:
       if  r a < r cso  then
16:
      Optimize the individuals by considering the opposite strategy and
17:
      calculating new solutions using Formula (26).
18:
      evaluate its fitness value and update the new nest with the old nest
19:
      update the nest with a better fitness value
20:
       end if
21:
      Generate a random number r b and compare it with r csbi using Formula (38)
22:
      if  r b < r csbi  then
23:
      Optimize the individuals considering linear global best strategy and
24:
      calculate new solutions by using Formula (37).
25:
      evaluate its fitness value and update the new nest with the old nest
26:
      update the nest with a better fitness value
27:
      end if
28:
   end
29:
   Until ( t < T max ) or (stop criterion)

3.6. Hybrid Strategy for DE and CS Algorithm

Based on the proposed BODE algorithm and improved CS algorithm, a multi-strategy serial framework was proposed to optimize the results of the IK problem. In the serial framework, we used a criterion to determine the algorithm to employ for optimizing the IK problem. The criterion is described as follows:
fit det = ( fit ave f it min f it max ) 2
Before the iteration, a random number r DECS between 0 and 1 was generated; then, we compared r DECS with f it det . If r DECS was less than f it det , then the improved CS algorithm would be applied; otherwise, the BODE would be used.
The schematic diagram of the BODE-CS algorithm is shown in Figure 1:

4. Simulation Result and Discussion

To realize the efficient demolition and rapid disposal of explosives, our team developed a new EOD robot, as shown in Figure 2. It consists of two systems: one is the main mechanical arm system (the left arm, with claw), and the other is the auxiliary mechanical arm system (the right arm, with the cutting tool).
The main manipulator has 6-DOF, which were used to capture and dispose of explosives, and the auxiliary manipulator has six degrees of freedom, which were used to disassemble explosives, as well as assist the main manipulator in observing and defusing explosives. In this paper, we selected the main manipulator as the object to analyze the proposed BODE-CS algorithm. The 3D structure diagram is shown in Figure 3.
The configuration of the main manipulator is shown in Figure 4:
The D–H parameters are shown in Table 2:
In Table 2, the parameters a, α , d, and θ represent link length, link twist angle, link offset, and joint angle, respectively.
The main idea involved in BODE-CS algorithms for solving inverse kinematics is to transform the problem to minimize a fitness function, so the final solution is only one. To validate the performance of the BODE-CS algorithm, two simulation experiments were designed: a random-points task and a trajectory-tracking task. The random-points task generated 100 random points and solved the IK problem according to these points. The trajectory-tracking task tracked the respective trajectories of four different curves. The specifications of the test machine were an Intel(R) Core(TM) i5-7500 CPU 3.40 GHz with 8.0 GB of RAM.

4.1. Parameter Setting

The aim of the simulations was to verify the performance of the BODE-CS algorithm to solve the IK problem. In the simulated experiment, several comparative experiments were designed to compare the performance among the BODE-CS algorithm, DE/rand/1 (Standard DE), DE/best/1, DE/rand/2, DE/best/2, DE/current–best/1, SDE [56], CS (Standard CS), PSO, GA, and ODE. A swarm size is typically 5–10 times the population dimension. The dimension of our robot manipulator was six, so we defined the swarm size of all the algorithms as 30. In this study, the robot’s manipulator position accuracy could reach 10 1 mm, so we defined the stop criterion as S stop = 1 × 10 6 mm. This criterion could not only compare the position accuracy of different algorithms, but could also meet the position accuracy requirements of robots. Based on the experience of scholars who have studied DE, CS, and other algorithms, we defined the maximum iteration number T max of all the algorithms as 100. The parameters of the BODE-CS algorithm were α l = 0.01, β = 3/2, and ω P = 1 . With many comparative experiments, when we selected λ = 0.1, F max = 0.9, F min = 0.5, w j = 0.7, w gbest = 0.3, C max = 0.8, C min = 0.5, C 0 = 0.2, C bi = 0.15, C csor = 0.05, P amax = 0.25 , and P amin = 0.05 , the BODE-CS algorithm showed better performance. Similarly, based on the experience of other scholars, we defined the factor F and C R in DE/rand/1, DE/rand/2, DE/best/1, DE/best/2, DE/current–best/1, SDE, and ODE, as 0.9 and 0.5, respectively; the factor λ in DE/rand/2, DE/best/2, and DE/current–best/1 was defined as 0.1.
The other algorithms’ parameter settings are shown in Table 3.
The c 1 and c 2 values represent the acceleration constant; P m represents mutation probability; and P c represents the crossover probability.
Before obtaining the coefficient ω R of the BODE algorithm, we used the Monte Carlo method to calculate the pos max and pos min and obtain λ p , where 300,000 random points were selected in the workspace to calculate pos max and pos min . Then, we calculated the λ p for a total of 30 independent times, the results are shown as follows:
Due to the pos max and pos min being affected by l arm , when calculating λ P using Formula (10), the difference between pos max and pos min divided by l arm . After that, when calculating ω R , λ R also divided by the sum of the difference between joint angle upper boundary and joint angle lower bounday in each dimension. As shown in Figure 5, the value of λ p approximated to ranges from 0.5725 to 0.5848. To reduce the increase in computational time caused by high-precision decimals, in this paper, we defined λ p = 0.58 .

4.2. Task Description

For Task 1, 100 randomly selected points were given, as shown in Figure 6. To ensure the desired random points were generated in the workspace, we used the Monte Carlo method to generate the random points. A comparative study of the IK problem of the random points was conducted. The position and the orientation of all the points were different. The influence of the different weight coefficients on the objective function was first tested; then, the fitness value f and position error P error were reported. Finally, the iterative processes of the different algorithms were also evaluated.
For Task 2, the trajectory-tracking simulation was conducted. In this task, we used sinusoidal, circular, trapezoidal, and rose curves to analyze the BODE-CS algorithm. The formulas of the four curves are shown in Formulas (43)–(46), the unit of the four curves is in mm. The main testing included the fitness value f , the position error P error , and so on. To display the statistical variation results of the simulation, a box plot was also used.
Trajectory 1: Sinusoidal
p x = 500 p y [ 520 , 520 + 300 π ] p z = 100 + 400 sin ( π 150 p y )
Trajectory 2: Circular
θ p [ 0 , 2 π ] p x = 500 p y = 200 + 300 sin ( θ p ) p z = 100 + 300 cos ( θ p )
Trajectory 3: Trapezoidal
p x = 500 p y [ 520 , 100 ] r p = 200 + 400 sin ( π 60 p y ) p z = 0 if r p > 0 400 if r p < 400 r p otherwise
Trajectory 4: Rose curve
p x = 500 β p [ 0 , π ] r p = 300 cos ( 3 β p ) p y = 520 + r p cos ( β p ) p z = r p sin ( β p )
The desired orientation matrix matrix of all the trajectories resulted in the following:
Rot = 0.2838 0.8639 0.4161 0.6716 0.1307 0.7293 0.6844 0.4865 0.5431

4.3. Simulation Results for the Robot IK Problem

4.3.1. Results Obtained for Task 1

Task 1 aimed to verify the performance of the proposed fitness function (Formula (6)). Several different coefficients were compared, and the results are shown in Figure 7.
To graphically display the statistical variation for the results, box plots were used. The smaller data distribution the algorithm shows, the better performance will be. The BODE-CS represents the weight coefficient of the proposed weight calculation method. As shown in Figure 7, when equipped with the proposed weight method, the fitness of the manipulator could guide the search of the algorithm to converge efficiently. An extensive performance comparison with seven weight coefficients indicates that the proposed BODE-CS reported small data distribution errors and showed the best performance among the eight weight coefficients. The results of the BODE-CS algorithm were precise, with a maximum value of fitness of 0.112. ω R was related to λ P , λ R and θ imax , θ imin ; λ P was related to pos max , pos min and l arm ; λ R was related to λ P ; and l arm was related to d i and a i . Thus, ω R was related to the robot structural parameters. The fitness value calculated by the proposed weight method (Formulas (6)–(12)) was smaller for the optimized coefficients when considering the robot structural parameters.
Additionally, to verify the performance of proposed strategies in the BODE-CS algorithm, we compared the k th point iteration process of the BODE-CS algorithm with other algorithms. Figure 8 shows the iteration results for the inverse kinematics problem of 100 random points. The reported results indicate that the proposed BODE-CS algorithm could balance the global search with the local search and outperformed the other algorithms, with a minimum fitness value of 0.0833. The second-lowest minimum fitness value among the other 10 algorithms was 0.3868 (CS). The DE/best-best/1 strategy made the BODE-CS algorithm have a fast convergence rate and better results; when the iteration number reached 63, the fitness value was less than 0.1. The BODE-CS algorithm showed faster convergence than the other algorithms.
Two parameters were used to compare the stability of the algorithms–the maximum fitness value and maximum position errors. The maximum position error and the maximum fitness value represented the maximum position error and the maximum fitness value of all the 100 random points, respectively. The results for solving the IK problem of 100 random points are illustrated in Table 4. The introduction of the algorithm selection function streamlined the balance between the global and local searches. As shown in Table 4, the BODE-CS had the best performance, with the lowest fitness value and position errors of all the algorithms.
To verify the influence of swarm size on the convergence results, four different-sized swarms were selected; the swarm sizes were 30, 50, 80, and 100; the S stop = 10 20 mm, and the results are shown in Figure 9.
As shown in Figure 9, with the increases in swarm size, the maximum fitness values of the iterations were always less than 0.15; the results for 30 individuals were similar to the other numbers of the individuals. The precision requirements for the explosive removal were not very high when the number of the trajectory or random points was less than 100. The smaller the swarm size was, the shorter the calculation time would be, so the swarm size selected in this study was appropriate.
Generally, the Jacobian-based method has the advantage of fast convergence and high precision; to verify the performance of the BODE-CS algorithm, we also compared the BODE-CS algorithm with the Newton–Raphson algorithm (Jacobian-based method). The initial solution of Newton–Raphson was set to [0 0 0 0 0 0]; the stop criterion of Newton–Raphson was equal to the BODE-CS algorithm. The comparison results of Newton–Raphson and the BODE-CS algorithm were shown ains Table 5:
The results show that, compared with the Newton–Raphson algorithm, the BODE-CS algorithm performed better, with a smaller mean or maximum position error, as well as mean or maximum fitness value. The Newton–Raphson algorithm showed a better minimum position error and fitness value. The precision of the Newton–Raphson algorithm was high; however, the solutions calculated by the Newton–Raphson algorithm were not stable. This is because of the influence of singular configuration and initial solution setting. In most situations, the precision of the Newton–Raphson algorithm is high; however, with the influence of singular configuration or initial solution setting, the result was difficult to converge. Thus, in general, the performance of the BODE-CS algorithm was better than Newton–Raphson.
In many situations, the EOD robot did not require high orientation accuracy when grabbing or defusing explosives. Thus, we designed another 100 random-points trjaectory task, which only considered the position requirements ( ω P = 1 , ω R = 0 in Formula (6)) to verify the applicability of the proposed algorithm in solving different tasks. The k th random point iteration process for different algorithms is shown below.
As shown in Figure 10, the proposed BODE-CS algorithm also outperformed the other algorithms. The algorithm selection function and other improved strategies kept the diversity and accelerated the swarm convergence, with a minimum fitness value of 0.00012. The second-lowest minimum fitness value among the other algorithms was 0.04316 (GA). When the iteration number reached 46, the fitness value of the BODE-CS algorithm was less than 0.1.
As shown in Formula (6), when ω R = 0 , the value of fitness is equal to the position error Δ P . Therefore, we only need to compare the maximum fitness value to select the best algorithm. As shown in Table 6, with the introduction of the improved Lévy flight strategy and the DE/best-best/1 strategy, the proposed algorithm could balance the global search and local search. The premature phenomenon could also be avoided. The simulation results of the BODE-CS strategies showed the best performance. The maximum fitness value of BODE-CS algorithm was 0.0075. It was also the smallest of all the algorithms.
To further verify the applicability of the BODE-CS algorithm, we introduced a 7-DOF Baxter redundant manipulator and solved its inverse kinematics problem of 100 random points. The coordinate system of link i, D–H parameters, and the distribution of 100 random points are shown in Figure 11, Table 7, and Figure 12, respectively. Therein, the offset of θ 2 is π / 2 .
Additionally, to verify the applicability of the BODE-CS algorithm, we compared the iterative process of the BODE-CS algorithm with other algorithms. The maximum iteration number T max was 200; the swarm size was 70. Figure 13 shows the iteration results for the inverse kinematics problem of 100 random points. The proposed BODE-CS algorithm outperformed the others, with a minimum fitness value of 0.0572. The second-lowest minimum fitness value among the other 10 algorithms was 0.1265 (DE/current-best/1). The BODE-CS algorithm had a fast convergence, and, when the iteration number reached 164, the fitness value was less than 0.1. The BODE-CS algorithm shows wide applicability and faster convergence than other algorithms.
The maximum fitness value and position error for solving the IK problem of 100 random points are illustrated in Table 8. The maximum position error and maximum fitness value were also used to compare the stability of the algorithms. The introduction of algorithm selection function makes it easy to balance the global search and local search in solving the 7-DOF IK problem. Therein, the BODE-CS algorithm also showed the best performance, with the smallest fitness value and position error in all the algorithms. The applicability of the widely used algorithm is further proved.

4.3.2. Results Obtained for Task 2

In Task 2, to better verify the performance of the BODE-CS algorithm, we selected 200 trajectory points for tracking. Due to the increase in the trajectory points, the calculations were more complex; thus, the probability of higher fitness values or position errors increased. Therefore, we redefined the swarm size as 60. As shown in Table 9, the maximum position errors corresponding to the IK solution of DE/current–best/1 and GA in the four curves were all more than 10 mm. Due to the relatively large maximum position error values, the IK solutions calculated by the two algorithms were unacceptable. Although the IK solutions obtained from the other eight algorithms were smaller, the cumulative error of adjacent points in a trajectory could considerably increase, and the stability of robot motion would be affected. The BODE-CS algorithm obtained the first rank with the minimal maximum position error and maximum fitness values in the four curves, and the maximum position errors of all four curves were less than 0.1 mm. The results show better performance than those of the other 10 algorithms.
To compare the trajectory-tracking results of all the algorithms in different curves, the fitness and postion distributions of all the algorithms were also analyzed. In Figure 14 and Figure 15, DE1, DE2, DE3, DE4, and DE5 represent DE/rand/1, DE/best/1, DE/best/2, DE/random/2, and DE/current-best/1, respectively. The position error results and fitness value results are displayed graphically. When the ω R was small, the influence of orientation error times ω R showed smaller values for the fitness function, so the position error was sometimes almost equal to the fitness value. For example, the results in Figure 14b were similar those in Figure 15b, so the fitness value analysis results were similar to the position error analysis results; thus, we only needed to discuss the analysis results for the position errors.
The position errors of the DE/current–best/1 and GA during the trajectory tracking were distributed over a large range. There are three reasons that may have influenced the results of DE/current–best/1 and GA: small swarm size, the quality of initial individuals, and the influence of the best individual. Due to the small swarm size and poor quality of initial solutions, the convergence of DE/current–best/1 and GA may have been slow, or premature phenomenon; if there are many same local best individuals in the swarm early on, the explore ability will decrease, and the swarm will show poor results. Therefore, the DE/current–best/1 and GA were not suitable for tracking the four trajectories. DE/best/1, DE/rand/1, and the other six algorithms had better performance results than DE/current–best/1 and GA; however, when compared to our proposed algorithm, their stabilities were poor, and the maximum position error was also large. Therefore, the proposed BODE-CS algorithm was the most suitable algorithm for trajectory tracking.
To further verify the trajectory tracking iteration results of the BODE-CS algorithm, we analyzed the iteration results of all the algorithms in four different curves. The results are shown as Figure 16, for all the trajectory iteration results generated by the algorithms, the BODE-CS algorithm acquired the first rank, with the following minimum fitness values: 0.065 (Trajectory 1), 0.059 (Trajectory 2), 0.100 (Trajectory 3), and 0.075 (Trajectory 4). Compared to the other algorithms, the BODE-CS algorithm also showed a rapid convergence rate when the fitness value reached 0.1. The iteration numbers when the fitness value reach 0.1 were 62 (Trajectory 1), 50 (Trajectory 2), 53 (Trajectory 3), and 43 (Trajectory 4). The proposed BODE-CS algorithm showed better convergence than the other algorithms.
Moreover, Figure 17, Figure 18, Figure 19 and Figure 20 show the Trajectory 1–4 tracking results of the DE/best/1 and BODE-CS algorithm, respectively. The black curve shows the desired trajectory, and the red point shows the calculation results using the DE/best/1 (Figure 17a) or BODE-CS (Figure 17b), respectively. The trajectory results showed that the DE/best/1 method presented a rough motion. The statical variation of the trajectory tracking showed a large data distribution. Compared to the DE/best/1 algorithm, the Lévy flight in the improved CS strategy led the proposed algorithm to search for a new environment, and the consistency of the BODE-CS algorithm showed a minimal data distribution. As compared to the DE/best/1 algorithm, the results indicated that the BODE-CS had more precise and accurate path-tracking results. The desired end-effector position and the obtained position were considered to be identical.

5. Conclusions and Future Developments

In this study, a novel hybrid BODE-CS algorithm was presented to solve the IK problem in robot manipulators. The simulated experiments were designed to verify the performance of our proposed hybrid algorithm for solving a trajectory-tracking problem. There are five contributions in this research. Firstly, a novel fitness function was formulated, which considered the robot’s structural requirements, which included the link length and offset, as well as the joint angle. The Monte Carlo method was also applied to calculate the weight coefficients of the orientation error. Compared to other weight coefficients, the algorithm accuracy was improved efficiently using the proposed novel fitness function. Then, the initial solutions were optimized using a Halton sequence and an opposite strategy to ensure the initial solutions were distributed more evenly in order for the solution quality to be improved. Moreover, multiple strategies were applied for DE and CS. The Lévy flight in the CS algorithm could improve the global search ability, and the limitations of using a single algorithm could be avoided; thus, a new function was designed to choose the proper algorithm. The scale factor F, the cross-over probability factor C r , a dynamically opposite strategy, and a bidirectional strategy were used to optimize the DE algorithm. Additionally, two typical DE algorithms were combined with the proposed strategies to form a novel composite DE algorithm. The CS was optimized with the linear best global strategy and dynamically opposite strategy. These strategies could efficiently enhance the exploration and explosive abilities. Finally, two tasks were designed, and the results showed that the BODE-CS algorithm outperformed the other 10 algorithms when solving the IK problem of 100 random points and for tracking different curve trajectories. The simulations showed that the BODE-CS algorithm showed the best performance of all the algorithms; the reported position error results of the BODE-CS algorithm were below 0.01 mm, with a swarm size of 30 and a maximum iteration of 100. The convergence rate was also superior to other algorithms when solving the 100 random-points task and the trajectory-tracking task. The results of the BODE-CS algorithm also showed consistent statistical results with minimal data distribution. Meanwhile, the applicability was also verified with a different fitness function, a 7 DOFs robot, and compared with Jacobian-based algorithm, respectively. The convergence rate and result also outperformed all the other algorithms.
However, although the proposed BODE-CS algorithm showed the better performance in solving the IK problem and trajectory tracking problem, there may be several limitions in this study. Firstly, we optimized the traditional DE algorithm with multiple strategies. Therefore, more control parameters were introduced; although the proposed algorithm showed better performance when solving the low dimensional problem (6 or 7 DOF robots), it may spend a lot of time to set the proper parameters when solving high dimensional (15 or more) problem. Secondly, more time was consumed by using the proposed algorithm to calculate the fitness value. The mean calculation time of the BODE-CS algorithm in Task 1 ( T max = 100, N = 30, repeat the calculation 30 times) was 7.96 s; the maximum mean calculation time of the other algorithms was 7.25 s (Cuckoo Search). Thirdly, when solving the trajectory tracking problem, we ignored the obstacle avoidance analysis. It was also an important issue when solving the trajectory-tracking problem in complex environments. Finally, the desired points in this paper were all in the workspace. If the desired point is not in the workspace, the motion of the mobile platform should be considered. Future research should design a strategy to balance the time consumption, and algorithm accuracy. The study should also focus on theoretical guidelines for selecting the proper parameter in the BODE-CS algorithm, the obstacle avoidance analysis, and the mobile platform also needs to be considered to complete the task in the complex environment.

Author Contributions

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

Funding

This research was funded by the National Key R&D Program of China (Grant No. 2016YFC0803005).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

Abbreviations

IK Inverse Kinematics
DE Differential Evolution
CS Cuckoo Search
BODE-CS Bidirectional Opposite Differential Evolution-Cuckoo Search
SDE Self-adaptive Differential Evolution
PSO Particle Swarm Optimizaiton
GA Genetic Algorithm

References

  1. Galicki, M. Optimal cascaded control of mobile manipulators. Nonlinear Dyn. 2019, 96, 1367–1389. [Google Scholar] [CrossRef] [Green Version]
  2. Fan, X.; Wang, J.; Wang, H.; Yang, L.; Xia, C. LQR trajectory tracking control of unmanned wheeled tractor based on improved quantum genetic algorithm. Machines 2023, 11, 62. [Google Scholar] [CrossRef]
  3. Song, H.; Li, G.; Li, Z.; Xiong, X. Trajectory control strategy and system modeling of load-sensitive hydraulic excavator. Machines 2023, 11, 10. [Google Scholar] [CrossRef]
  4. Ghasemi, A.; Eghtesad, M.; Farid, M. Neural Network Solution for Forward Kinematics Problem of Cable Robots. J. Intell. Robot. Syst. 2010, 60, 201–215. [Google Scholar] [CrossRef]
  5. Liu, H.; Zhou, W.; Lai, X.; Zhu, S. An Efficient Inverse Kinematic Algorithm for a PUMA560-Structured Robot Manipulator. Int. J. Adv. Robot. 2013, 10, 1–5. [Google Scholar] [CrossRef]
  6. Khan, H.; Abbasi, S.J.; Lee, M.C. DPSO and inverse Jacobian-Based real-time inverse kinematics with trajectory tracking using integral SMC for teleoperation. IEEE Access 2020, 8, 159622–159638. [Google Scholar] [CrossRef]
  7. Sekkat, H.; Tigani, S.; Saadane, R.; Chehri, A. Vision-based robotic arm control algorithm using deep reinforcement learning for autonomous objects grasping. Appl. Sci. 2021, 11, 7917. [Google Scholar] [CrossRef]
  8. Kucuk, S.; Bingul, Z. Inverse kinematics solutions for industrial robot manipulators with offset wrists. Appl. Math. Model. 2014, 38, 1983–1999. [Google Scholar] [CrossRef]
  9. Gong, M.; Li, X.; Zhang, L. Analytical inverse kinematics and self-motion application for 7-DOF redundant manipulator. IEEE Access 2019, 7, 18662–18674. [Google Scholar] [CrossRef]
  10. Sekiguchi, M.; Takesue, N. Fast and robust numerical method for inverse kinematics with prioritized multiple targets for redundant robots. Adv. Robot. 2020, 34, 1068–1078. [Google Scholar] [CrossRef]
  11. Shi, J.; Mao, Y.; Li, P.; Liu, G.; Liu, P.; Yang, X.; Wang, D. Hybrid mutation fruit fly optimization algorithm for solving the inverse kinematics of a redundant robot manipulator. Math. Probl. Eng. 2020, 2020, 6315675. [Google Scholar] [CrossRef]
  12. Featherstone, R. Position and velocity transformations between robot end-effector coordinates and joint angles. Int. J. Robot. Res. 1983, 2, 35–45. [Google Scholar] [CrossRef]
  13. Gan, J.Q.; Oyama, E.; Rosales, E.M.; Hu, H. A complete analytical solution to the inverse kinematics of the pioneer 2 robotic arm. Robotica 2005, 23, 123–129. [Google Scholar] [CrossRef]
  14. 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] [Green Version]
  15. Kumar, V.; Sen, S.S.; Roy, S.; Dasa, S.K.; Shome, S.N. Inverse kinematics of redundant manipulator using interval newton method. Int. J. Eng. Manuf. 2015, 5, 19–29. [Google Scholar] [CrossRef] [Green Version]
  16. Kuo, Y.L.; Lin, T.P.; Wu, C.Y. Experimental and numerical study on the semi-closed loop control of a planar parallel robot manipulator. Math. Probl. Eng. 2014, 2014, 769038. [Google Scholar] [CrossRef] [Green Version]
  17. Amiri, S.M.; Ramli, R. Intelligent trajectory tracking behavior of a multi-joint robotic arm via genetic–swarm optimization for the inverse kinematic solution. Sensors 2021, 21, 3171. [Google Scholar] [CrossRef]
  18. Zhu, Z.; Liu, Y.; He, Y.; Wu, W.; Wang, H.; Huang, C.; Ye, B. Fuzzy PID control of the three-degree-of-freedom parallel mechanism based on genetic algorithm. Appl. Sci. 2022, 12, 11128. [Google Scholar] [CrossRef]
  19. Rokbani, N.; Alimi, A.M. Inverse Kinematics Using Particle Swarm Optimization, A Statistical Analysis. Procedia Eng. 2013, 64, 1602–1611. [Google Scholar] [CrossRef] [Green Version]
  20. 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]
  21. Ibarra-Pérez, T.; Ortiz-Rodríguez, J.M.; Olivera-Domingo, F.; Guerrero-Osuna, H.A.; Gamboa-Rosales, H.; Martínez-Blanco, M.d.R. A novel inverse kinematic solution of a six-DOF robot using neural networks based on the taguchi optimization technique. Appl. Sci. 2022, 12, 9512. [Google Scholar] [CrossRef]
  22. El-Sherbiny, A.; Elhosseini, M.A.; Haikal, A.Y. A new ABC variant for solving inverse kinematics problem in 5 DOF robot arm. Appl. Soft Comput. 2018, 73, 24–38. [Google Scholar] [CrossRef]
  23. Zhang, T.; Cheng, Y.; Wu, H.; Song, Y.; Yan, S.; Handroos, H.; Zheng, L.; Ji, H.; Pan, H. Dynamic accuracy ant colony optimization of inverse kinematic (DAACOIK) analysis of multi-purpose deployer (MPD) for CFETR remote handling. Fusion Eng. Des. 2020, 156, 111522. [Google Scholar] [CrossRef]
  24. Price, K.; Storn, R.; Lampinen, J. The Differential Evolution Algorithm; Springer: Berlin/Heidelberg, Germany, 2005; pp. 37–134. [Google Scholar] [CrossRef]
  25. Kennedy, J.; Eberhart, R. Particle swarm optimization. In Proceedings of the ICNN’95-International Conference on Neural Networks, Perth, WA, Australia, 27 November–1 December 1995. [Google Scholar] [CrossRef]
  26. Yang, X.S.; Deb, S. Cuckoo search via Lévy flights. In Proceedings of the IEEE 2009 World Congress on Nature & Biologically Inspired Computing (NaBIC), Coimbatore, India, 9–11 December 2009. [Google Scholar] [CrossRef]
  27. Dorigo, M.; Maniezzo, V.; Colorni, A. Ant system: Optimization by a colony of cooperating agents. IEEE Trans. Syst. Man Cybern. Part B 1996, 26, 29–41. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  28. Tuğrul, Ç.; Milani, M.; Alavi, M. A new heuristic spproach for inverse kinematics of robot arms. Adv. Sci. Lett. 2013, 19, 329–333. [Google Scholar] [CrossRef]
  29. McCulloch, W.S.; Pitts, W. A logical calculus of the ideas immanent in nervous activity. Bull. Math. Biophys. 1943, 5, 115–133. [Google Scholar] [CrossRef]
  30. Momani, S.; Zaer, A.; Alsmadi, P. Solution of Inverse Kinematics Problem using Genetic Algorithms. Appl. Math. Inform. Sci. 2015, 10, 225–233. [Google Scholar] [CrossRef]
  31. Storn, R.; Price, K. Differential evolution-a simple and efficient heuristic for global optimization over continuous spaces. J. Glob. Optim. 1997, 11, 341–359. [Google Scholar] [CrossRef]
  32. Storn, R. Designing nonstandard filters with differential evolution. IEEE Signal Process. Mag. 2005, 22, 103–106. [Google Scholar] [CrossRef]
  33. Bhandari, A.K.; Kumar, A.; Chaudhary, S.; Singh, G.K. A new beta differential evolution algorithm for edge preserved colored satellite image enhancement. Multidimens. Syst. Signal Process. 2017, 28, 495–527. [Google Scholar] [CrossRef]
  34. 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]
  35. Sandi, B.Š.; Anđelić, N.; Lorencin, I.; Saga, M.; Car, Z. Path planning optimization of six-degree-of-freedom robotic manipulators using evolutionary algorithms. Int. J. Adv. Robot. Syst. 2020, 617, 1–16. [Google Scholar] [CrossRef] [Green Version]
  36. Wang, M.; Luo, J.; Fang, J.; Yuan, J. Optimal trajectory planning of free-floating space manipulator using differential evolution algorithm. Adv. Space Res. 2018, 61, 1525–1536. [Google Scholar] [CrossRef]
  37. Sánchez-Sánchez, P.; Cebada-Reyes, J.G.; Ruiz-García, A.; Montiel-Martínez, A.; Reyes-Cortés, F. Differential evolution algorithms comparison used to tune a visual control law. IEEE Access 2022, 10, 46028–46042. [Google Scholar] [CrossRef]
  38. 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] [Green Version]
  39. 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]
  40. Zhang, M.; Wang, H.; Cui, Z.; Chen, J. Hybrid multi-objective cuckoo search with dynamical local search. Memet. Comput. 2018, 10, 199–208. [Google Scholar] [CrossRef]
  41. Tran-Ngoc, H.; Khatir, S.; Roeck, D.G.; Bui-Tien, T.; Wahab, M.A. An efficient artificial neural network for damage detection in bridges and beam-like structures by improving training parameters using cuckoo search algorithm. Eng. Struct. 2019, 199, 109637. [Google Scholar] [CrossRef]
  42. Benkhaira, S.; Layeb, A. Face recognition using RLDA method based on mutated cuckoo search algorithm to extract optimal features. Int. J. Appl. Metaheuristic Comput. 2020, 11, 118–133. [Google Scholar] [CrossRef]
  43. Wang, W.; Tao, Q.; Cao, Y.; Wang, X.; Zhang, X. Robot time-optimal trajectory planning based on improved cuckoo search algorithm. IEEE Access 2020, 8, 86923–86933. [Google Scholar] [CrossRef]
  44. Saraswathi, M.; Murali, G.B.; Deepak, B. Optimal path planning of mobile robot using hybrid cuckoo search-bat algorithm. Procedia Comput. Sci. 2018, 133, 510–517. [Google Scholar] [CrossRef]
  45. Sharma, K.; Singh, S.; Doriya, R. Optimized cuckoo search algorithm using tournament selection function for robot path planning. Int. J. Adv. Robot. Syst. 2021, 18, 172988142199613. [Google Scholar] [CrossRef]
  46. Zhang, L.; Wang, Y.; Zhao, X.; Zhao, P.; He, L. Time-Optimal trajectory planning of serial manipulator based on adaptive cuckoo search algorithm. J. Mech. Sci. Technol. 2021, 35, 3171–3181. [Google Scholar] [CrossRef]
  47. Karahan, O.; Karci, H.; Tangel, A. Optimal trajectory generation in joint space for 6R industrial serial robots using cuckoo search algorithm. Intell. Serv. Robot. 2022, 15, 627–648. [Google Scholar] [CrossRef]
  48. Sanz, P. Robotics: Modeling, Planning, and Control. IEEE Robot. Autom. Mag. 2009, 16, 101. [Google Scholar] [CrossRef]
  49. Mueller, A. Modern Robotics: Mechanics, Planning, and Control. IEEE Control Syst. Mag. 2019, 39, 100–102. [Google Scholar] [CrossRef]
  50. Rahnamayan, S.; Wang, G.G. Solving large scale optimization problems by opposition-based differential evolution (ODE). WSEAS Trans. Comput. 2008, 7, 1792–1804. Available online: http://www.sfu.ca/~gwa5/index_files/Shahr-WES.pdf (accessed on 12 January 2023).
  51. Li, G.; Lin, Q.; Cui, L.; Du, Z.; Liang, Z.; Chen, J.; Lu, N.; Ming, Z. A novel hybrid differential evolution algorithm with modified CoDE and JADE. Appl. Soft Comput. 2016, 47, 577–599. [Google Scholar] [CrossRef]
  52. Li, S.; Gong, W.; Yan, X.; Hu, C.; Bai, D.; Wang, L. Parameter estimation of photovoltaic models with memetic adaptive differential evolution. Sol. Energy 2019, 190, 465–474. [Google Scholar] [CrossRef]
  53. Li, J.; Ding, Y.; Wei, H.; Zhang, Y.; Lin, W. SimpleTrack: Rethinking and improving the JDE approach for multi-object tracking. Sensors 2022, 22, 5863. [Google Scholar] [CrossRef]
  54. Angira, R.; Babu, B.V. Non-Dominated sorting differential evolution (NSDE): An extension of differential evolution for multi-objective optimization. In Proceedings of the 2nd Indian International Conference on Artificial Intelligence, Pune, India, 20–22 December 2005; Available online: https://www.researchgate.net/publication/220888373_Non-dominated_Sorting_Differential_Evolution_NSDE_An_Extension_of_Differential_Evolution_for_Multi-objective_Optimization (accessed on 15 January 2023).
  55. Du, S.Y.; Liu, Z.G. Hybridizing particle swarm optimization with JADE for continuous optimization. Multimed. Tools Appl. 2020, 79, 4619–4636. [Google Scholar] [CrossRef]
  56. Hernandez-Barragan, J.; Lopez-Franco, C.; Arana-Danieland, N.; Alani, A.Y. Inverse kinematics for cooperative mobile manipulators based on self-adaptive differential evolution. PeerJ Comput. Sci. 2021, 7, e419. [Google Scholar] [CrossRef]
  57. Mutti, S.; Nicola, G.; Beschi, M.; Pedrocchi, N.; Tosatti, L.M. Towards optimal task positioning in multi-robot cells, using nested meta-heuristic swarm algorithms. Robot. Comput.-Integr. Manuf. 2021, 71, 102131. [Google Scholar] [CrossRef]
  58. Soneji, H.; Sanghvi, R.C. Towards the Improvement of Cuckoo Search Algorithm. In Proceedings of the 2012 World Congress on Information and Communication Technologies (IEEE), Trivandrum, India, 30 October–2 November 2012. [Google Scholar] [CrossRef]
Figure 1. The schematic diagram of BODE-CS algorithm.
Figure 1. The schematic diagram of BODE-CS algorithm.
Machines 11 00648 g001
Figure 2. The schematic of the explosive ordnance disposal robot.
Figure 2. The schematic of the explosive ordnance disposal robot.
Machines 11 00648 g002
Figure 3. The 3D structure diagram of the main manipulator.
Figure 3. The 3D structure diagram of the main manipulator.
Machines 11 00648 g003
Figure 4. The configuration of the main manipulator using standard D–H method.
Figure 4. The configuration of the main manipulator using standard D–H method.
Machines 11 00648 g004
Figure 5. The results of λ P in the repeated calculation using the Monte Carlo method.
Figure 5. The results of λ P in the repeated calculation using the Monte Carlo method.
Machines 11 00648 g005
Figure 6. The distribution of 100 random points.
Figure 6. The distribution of 100 random points.
Machines 11 00648 g006
Figure 7. Fitness value results for different ω R .
Figure 7. Fitness value results for different ω R .
Machines 11 00648 g007
Figure 8. The k th random point iteration process with different algorithms.
Figure 8. The k th random point iteration process with different algorithms.
Machines 11 00648 g008
Figure 9. The fitness value results for different swarm sizes.
Figure 9. The fitness value results for different swarm sizes.
Machines 11 00648 g009
Figure 10. The k th random point iteration process of different algorithms (position requirements).
Figure 10. The k th random point iteration process of different algorithms (position requirements).
Machines 11 00648 g010
Figure 11. The coordinate system of Baxter’s manipulator using modified D–H method.
Figure 11. The coordinate system of Baxter’s manipulator using modified D–H method.
Machines 11 00648 g011
Figure 12. A distribution of 100 random points for 7-DOF robot IK problem.
Figure 12. A distribution of 100 random points for 7-DOF robot IK problem.
Machines 11 00648 g012
Figure 13. The k th random point iteration process of different algorithms.
Figure 13. The k th random point iteration process of different algorithms.
Machines 11 00648 g013
Figure 14. Fitness value results for robot trajectories.
Figure 14. Fitness value results for robot trajectories.
Machines 11 00648 g014
Figure 15. Position error results for robot trajectories.
Figure 15. Position error results for robot trajectories.
Machines 11 00648 g015
Figure 16. The iteration results of Task 2 with different algorithms. (a) Sinusoidal. (b) Circular. (c) Trapezoidal. (d) Rose curve.
Figure 16. The iteration results of Task 2 with different algorithms. (a) Sinusoidal. (b) Circular. (c) Trapezoidal. (d) Rose curve.
Machines 11 00648 g016
Figure 17. Trajectory 1 tracking results based on BODE-CS algorithm and DE/best/1 algorithm. (a) DE/best/1 algorithm. (b) BODE-CS algorithm.
Figure 17. Trajectory 1 tracking results based on BODE-CS algorithm and DE/best/1 algorithm. (a) DE/best/1 algorithm. (b) BODE-CS algorithm.
Machines 11 00648 g017
Figure 18. Trajectory 2 tracking results based on BODE-CS algorithm and DE/best/1 algorithm. (a) DE/best/1 algorithm. (b) BODE-CS algorithm.
Figure 18. Trajectory 2 tracking results based on BODE-CS algorithm and DE/best/1 algorithm. (a) DE/best/1 algorithm. (b) BODE-CS algorithm.
Machines 11 00648 g018
Figure 19. Trajectory 3 tracking results based on BODE-CS algorithm and DE/best/1 algorithm. (a) DE/best/1 algorithm. (b) BODE-CS algorithm.
Figure 19. Trajectory 3 tracking results based on BODE-CS algorithm and DE/best/1 algorithm. (a) DE/best/1 algorithm. (b) BODE-CS algorithm.
Machines 11 00648 g019
Figure 20. Trajectory 4 tracking results based on BODE-CS algorithm and DE/best/1 algorithm. (a) DE/best/1 algorithm. (b) BODE-CS algorithm.
Figure 20. Trajectory 4 tracking results based on BODE-CS algorithm and DE/best/1 algorithm. (a) DE/best/1 algorithm. (b) BODE-CS algorithm.
Machines 11 00648 g020
Table 1. A comparison of different algorithms in terms of their advantages, disadvantages, and limitations.
Table 1. A comparison of different algorithms in terms of their advantages, disadvantages, and limitations.
AdvantagesDisadvantagesLimitation
DE [24]fast convergence, strong robustness, and easy to hybridize with other algorithmseasily influenced by local optima, premature convergence, and even search stagnationlack of theoretical analysis of convergence
PSO [25]fast convergence, few control parameters, strong robustnesseasily influenced by local optima, premature convergencepoor discrete optimization results
CS [26]few control parameters, convergence, hard to fall into the local optimal, easy to hybridize with other algorithms, strong global search ability.slow convergence rate and lack of vitalitydifficult to set the search step-size; better individuals may be discarded in the search process; poor local search ability
ACS [27]strong robustness; easy to hybridize with other algorithmstime intensive, slow convergence rate, and easily influenced by local optimumweak ability to balance the population diversity and convergence rate
ABC [28]high global search ability, simple parameter setting, and wide range of applicationslow convergence low precisionsensitive to parameter setting
NN [29]highly parallelized, robust, and fault tolerantsensitive to data quality and noise; requires a lot of data and computing resourcesthe learning process cannot be explained, and the computing rate of neural network is slow
GA [30]strong explore ability, suitable for nonlinear problems, hard to fall into local optimumthe programming is complicated to implement, and easy to fall into local optimal solutionsthe results is very dependent on the encoding scheme; the convergence speed is slow; and the parameter adjustment is difficult
Table 2. D–H parameter settings for EOD robot manipulator.
Table 2. D–H parameter settings for EOD robot manipulator.
ia (mm) α (rad)d (mm) θ max (rad) θ min (rad)
10 π 2 113.5 π 2 π 2
2−42500 π 2 π 2
3−374.900 π 2 π 2
40 π 2 92.8 π 2 π 2
50 π 2 110.3 π 2 π 2
60056.8 π 2 π 2
Table 3. The parameter setting of CS, PSO, and GA.
Table 3. The parameter setting of CS, PSO, and GA.
AlgorithmParameter Setting
CS P a = 0.25, α l = 0.01, α g = 1, β = 3/2
PSO c 1 = 1.2; c 2 = 1.2;
GA P m = 0.2, P c = 0.4,
Table 4. Inverse kinematics with 100 random points using different algorithms.
Table 4. Inverse kinematics with 100 random points using different algorithms.
AlgorithmMaximum Position Error (mm)Maximum Fitness Value
BODE-CS0.0700.112
DE/rand/113.48413.552
DE/best/16.7706.874
DE/best/211.46611.466
DE/rand/212.93912.939
DE/current-best/1129.239129.253
SDE [56]15.35915.385
CS10.89710.898
PSO14.96315.213
GA78.27178.377
ODE16.69416.705
Table 5. The comparison results of Newton–Raphson and BODE-CS in solving 100 random-points task.
Table 5. The comparison results of Newton–Raphson and BODE-CS in solving 100 random-points task.
AlgorithmPosition Error (mm)Fitness Value
MinMeanMaxMinMeanMax
BODE-CS 7.184 × 10 6 5.895 × 10 4 0.0070 9.690 × 10 3 6.707 × 10 2 0.112
Newton-Raphson 2.842 × 10 14 57.1501427.9 2.843 × 10 14 57.1511427.9
Table 6. Inverse kinematics with 100 random points using different algorithms (position requirement).
Table 6. Inverse kinematics with 100 random points using different algorithms (position requirement).
AlgorithmMaximum Fitness Value
BODE-CS0.0075
DE/rand/115.9222
DE/best/19.0836
DE/best/27.8957
DE/rand/214.5838
DE/current-best/1161.2696
SDE15.5102
CS12.461
PSO52.8607
GA110.2148
ODE18.4566
Table 7. Baxter’s Denavit–Hartenberg parameters.
Table 7. Baxter’s Denavit–Hartenberg parameters.
ia (mm) α (rad)d (mm) θ max (rad) θ min (rad)
100270.35 π 2 π 2
20 π 2 69 π 3 π 2
30 π 2 364.35 π 2 π 2
469 π 2 0 π 2 0
50 π 2 374.29 π 2 π 2
610 π 2 0 π 2 π 2
70 π 2 229.529 π 2 π 2
Table 8. Inverse kinematics of a 7-DOF redundant robot manipulator with 100 random points using different algorithms.
Table 8. Inverse kinematics of a 7-DOF redundant robot manipulator with 100 random points using different algorithms.
Maximum Position Error (mm)Maximum Fitness Value
BODE-CS0.00620.1014
DE/rand/128.069028.14704
DE/best/119.951420.0162
DE/best/223.881323.9331
DE/rand/220.877820.9458
DE/current-best/146.356046.4510
SDE24.860124.9414
CS3.15453.1707
PSO36.256636.3429
GA62.016362.1044
ODE21.311821.3953
Table 9. The results of four curves trajectories tracked using different algorithms.
Table 9. The results of four curves trajectories tracked using different algorithms.
AlgorithmTrajectory 1 Trajectory 2 Trajectory 3 Trajectory 4
Maximum
Position
Error
Maximum
Fitness
Value
Maximum
Position
Error
Maximum
Fitness
Value
Maximum
Position
Error
Maximum
Fitness
Value
Maximum
Position
Error
Maximum
Fitness
Value
BODE-CS0.0170.1000.0160.1200.0040.1100.0830.182
DE/rand/17.7067.7136.9466.9589.2549.3568.568.635
DE/best/14.7794.8324.8954.8976.4466.4724.0834.155
DE/best/24.7824.7844.2004.2147.7857.8064.4154.425
DE/rand/27.3037.3477.7727.7909.9439.9787.3847.413
DE/current-best/143.99944.00973.68073.70049.42149.44554.27854.322
SDE11.41911.43911.67211.71310.02510.0309.2399.299
CS4.5384.6104.6494.6614.0364.1394.8714.954
PSO4.1114.1545.2035.2492.4662.5356.5776.594
GA41.72141.75848.61348.65646.98147.00443.83143.874
ODE10.54310.54810.67210.7409.5849.65810.16310.179
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.; Luo, X.; Qiao, L. Inverse Kinematics of Robot Manipulator Based on BODE-CS Algorithm. Machines 2023, 11, 648. https://doi.org/10.3390/machines11060648

AMA Style

Li M, Luo X, Qiao L. Inverse Kinematics of Robot Manipulator Based on BODE-CS Algorithm. Machines. 2023; 11(6):648. https://doi.org/10.3390/machines11060648

Chicago/Turabian Style

Li, Minghao, Xiao Luo, and Lijun Qiao. 2023. "Inverse Kinematics of Robot Manipulator Based on BODE-CS Algorithm" Machines 11, no. 6: 648. https://doi.org/10.3390/machines11060648

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