Next Article in Journal
Rivers’ Water Level Assessment Using UAV Photogrammetry and RANSAC Method and the Analysis of Sensitivity to Uncertainty Sources
Next Article in Special Issue
PLI-VINS: Visual-Inertial SLAM Based on Point-Line Feature Fusion in Indoor Environment
Previous Article in Journal
A Novel Path Planning Strategy for a Cleaning Audit Robot Using Geometrical Features and Swarm Algorithms
Previous Article in Special Issue
An Improved Mixture Density Network for 3D Human Pose Estimation with Ordinal Ranking
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Novel Hybrid Algorithm for the Forward Kinematics Problem of 6 DOF Based on Neural Networks

1
Engineering Research Center for Intelligent Production Line Equipment of Hubei Province, School of Computer Science and Engineering Artificial Intelligence, Wuhan Institute of Technology, Wuhan 430205, China
2
School of Computer Science, South-Central Minzu University, Wuhan 430074, China
3
School of Information Science and Engineering, Wuhan University of Science and Technology, Wuhan 430081, China
4
Key Laboratory of Image Processing and Intelligent Control, School of Automation, Huazhong University of Science and Technology, Wuhan 430074, China
*
Author to whom correspondence should be addressed.
Sensors 2022, 22(14), 5318; https://doi.org/10.3390/s22145318
Submission received: 15 June 2022 / Revised: 3 July 2022 / Accepted: 9 July 2022 / Published: 16 July 2022

Abstract

:
The closed kinematic structure of Gough–Stewart platforms causes the kinematic control problem, particularly forward kinematics. In the traditional hybrid algorithm (backpropagation neural network and Newton–Raphson), it is difficult for the neural network part to train different datasets, causing training errors. Moreover, the Newton–Raphson method is unable to operate on a singular Jacobian matrix. In this study, in order to solve the forward kinematics problem of Gough–Stewart platforms, a new hybrid algorithm is proposed based on the combination of an artificial bee colony (ABC)–optimized BP neural network (ABC–BPNN) and a numerical algorithm. ABC greatly improves the prediction ability of neural networks and can provide a superb initial value to numerical algorithms. In the design of numerical algorithms, a modification of Newton’s method (QMn-M) is introduced to solve the problem that the traditional algorithm model cannot be solved when it is trapped in singular matrix. Results show that the maximal improvement in ABC–BPNN error optimization was 46.3%, while the RMSE index decreased by 42.1%. Experiments showed the feasibility of QMn-M in solving singular matrix data, while the percentage improvement in performance for the average number of iterations and required time was 14.4% and 13.9%, respectively.

1. Introduction

Gough–Stewart platforms (GSPs) are typical six-degree-of-freedom (6-DOF) parallel robots that have the advantages of high rigidity, high precision, and large carrying capacity [1]. GSPs are widely used in various large-scale motion simulation platforms such as flight, automotive, ship, and tank simulators. Generally, GSPs comprise three structures: universal and cylindrical and universal joint (6-UCU), 6-UPS, and 6-SPS, in which 6 represents six identical structures, U represents a universal joint, C represents a cylindrical joint, P represents a prismatic joint, and S represents a spherical joint. GSPs can be divided into 6–6, 3–3, and 6–3 structures according to the connection modes of the upper and lower hinge points. In this paper, the 6-UCU structure and 6–6 connection model are used. GSPs, with its structure and benefits, compensates for the many deficiencies of serial robots. It has a wide variety of applications in the future industry and intelligent manufacturing.
Because it can give mapping between a Cartesian and joint space, the kinematics problem is critical for parallel robotics. Solving the forward kinematics problem (FKP) is an essential step in the modeling and control of parallel robots, particularly for real-time applications. The FKP is a challenging and essential robotics topic in GSPs. Due to the high nonlinearity and the varied closed-loop kinematic architectures of parallel robots [2], there is currently no acknowledged generic solution to solve the FKP. To control GSPs, advanced algorithms with higher computation loads that achieve better performance can be used. Therefore, it is significant to find a more powerful algorithm to reduce the computation time of the FKP. The FKP of GSPs is, therefore, a hot topic for researchers.
Studies on the FKP of GSPs can be classified into the traditional approach and the intelligent algorithm approach. Conventional traditional approaches include the numerical method, analytical method, and adding extra sensors. The numerical method can obtain an iterative solution without suffering the multisolution problem [3]. The Newton–Raphson (NR) method is a prominent numerical approach for analyzing a parallel robot’s forward kinematics [4]. The NR method with good initial values is used to numerically solve nonlinear FKP equations for root finding. The method is overly sensitive to initial values, and results diverge if the initial values are inappropriate. The analytical method tends to find a closed-form solution [5,6]. This method forms a series of sophisticated derivations and is only useful for certain structures. The method of adding more sensors [7] is a strategy to find a unique approach with the least amount of computing. Unfortunately, due to the high cost of this method, and measurement and assembly faults, its application range is limited.
With the advancement of computer application technology and artificial intelligence, an increasing number of researchers have begun to use intelligent algorithms to solve the FKP, such as artificial neural networks (ANNs) and support vector machines (SVM). Morell et al. [8] solved FKP by using the support vector regression approach, which had a unique notion, but the model training time was too long and would not completely satisfy the requirements in real-time control. ANNs are employed in the field of intelligent algorithms to train the inverse kinematics values of the GSP to produce a set of forward kinematics solutions [9]. Subsequently, the NR method is used to obtain the exact values of the approximations. Using the hybrid strategy to solve FKP has been recognized by some scholars. This hybrid strategy [10] can be combined with a high level of solving speed and accuracy. Moreover, it can leverage the superb initial value provided by a neural network to perform a Newtonian iteration, which compensates for the Newtonian iteration’s sensitivity to the initial value. It also overcomes the problem of a neural network’s predicted value having a forecasting deviation. The approach is adaptable to parallel robots with a variety of structural properties [11]. Many researchers have used this foundation to improve the algorithm’s efficiency and accuracy in real-time motion. To ensure the feasibility of real-time application, Zhu et al. exploited the optimization of numerical iteration efficiency by creating a deviation-driven algorithm [12]. After that, a velocity Jacobian matrix iteration was used to improve the hybrid algorithm’s overall speed [13]. The advantages of the neural network and genetic algorithm are combined in the neurogenetic algorithm [14], which maximizes the robot’s workspace volume.
For the neural network part, the well-known BP neural network (BPNN) is mostly employed in the traditional hybrid strategy. BPNN has good nonlinear mapping ability, i.e., f { L O 1 , L O 2 , L O 3 , L O 4 , L O 5 , L O 6 } { α , β , γ , x , y , z } , which is the relationship between joint displacement and end-effector pose. Although the BPNN model can achieve promising performance and has a flexible network structure, it still has some drawbacks: (i) For BPNNs, the training effect depends on the dataset, i.e., limited self-adaptation ability for different datasets. (ii) It is possible to fall into a local optimum for the model system with six inputs and six outputs, which cannot ensure a global training effect. (iii) The model is sensitive to initial parameters. Randomly initializing weights and thresholds impacts the model. Moreover, there is also a flaw with the numerical algorithm part. (iv) A set of inverse of Jacobian matrices J 1 are formed in the process of solving nonlinear equations with the Newton–Raphson method [12]. That is, when the Jacobian matrix is singular, the equations have no solution. On the basis of the above problems, this paper proposes a novel hybrid algorithm that can guarantee efficient and accurate problem solving, so that any value input to the mechanism under the feasible motion space can have a solution, rendering it a universal algorithm for the 6-DOF forward kinematics problem.
The major contributions of our work are as follows:
  • An optimization method via an artificial bee colony (ABC) to optimize the BPNN (ABC–BPNN) is proposed. Good weights and thresholds are obtained through the process of the ABC’s population iteration to prevent the training model from falling into a local optimum.
  • A modification of Newton’s method for solving nonlinear equations with a singular Jacobian matrix is introduced.
  • We used QMn-M (a modification of Newton’s method from Lv et al. [15]) combined with a simplified Newtonian iteration (SNR).
  • We used the length error threshold to reduce the frequency of ANN calls to improve the efficiency of real-time control.
First, ABC–BPNN [16] was employed to achieve outstanding prediction values, adjust them to the requirements of this hybrid strategy, and improve the overall strategy convergence and computing performance. Second, the QMn-M algorithm [15] can effectively solve the problem of a numerical method for solving forward kinematics suffering from a singular Jacobian matrix. Third, the global Newton–Raphson method with monotonic descent (GNRDM) proposed by Yang et al. [17] was combined with SNR to improve the efficiency of the algorithm [12]. Inspired by this technique, we used QMn-M combined with SNR to ensure the accuracy of numerical solutions. Moreover, it can reduce the computation time and iterations in overall algorithm. Lastly, the length error threshold ε 0 was designed into the overall algorithm process to determine whether the previous set of solutions Q p r e satisfied the required value of the current iteration. If this is the case, it is directly used to carry out SNR. As a result, the frequent invocation of ANNs can be reduced. The overall operation efficiency and the problem-solving efficiency of ANNs in real-time motion control can be improved.
The structure of this paper is as follows: In Section 2, we describe the establishment of the kinematics model of GSP, including inverse kinematics problem analysis and the established FKP equations of GSP. The structure of ANNs and the proposed ABC–BPNN applied on the FKP is described in Section 3. Section 4 mainly describes the design and analysis of numerical algorithms. Section 5 outlines a comparative experiment that was conducted on a neural network and numerical algorithm. Lastly, Section 6 concludes the paper.

2. Kinematics Model of GSPs

2.1. Inverse Kinematics

Compared with the FKP, the inverse kinematics problem (IKP) is relatively easy. The GSP consists of two platforms that are connected by several links, as shown in Figure 1. The base platform is fixed to the ground, and the mobile platform works as the end effector. The motion of six links causes the movement of the end effector.
According to Figure 1, the coordinates of the six lower hinge points are defined as A i ( i = 1 , 2 , , 6 ) , the coordinates of the six upper hinge points are B i ( i = 1 , 2 , , 6 ) . L i ( i = 1 , 2 , , 6 ) is the length of the link between the connection point A i and B i at initial state. The radii of the six lower- and higher-hinge points are R 1 and R 2 respectively, as shown in Figure 2.
The overall structure of 6–6 GSP and its initial state coordinate system are shown in Figure 2. For the base coordinate system A , defined by its base platform and its origin O A in the platform’s geometric center. The moving coordinate system B is attached to the mobile platform, with its origin O B at the platform’s geometric center.
The IKP is to calculate the value of joint variable L O i by giving the pose of the moving coordinate system. The pose of moving coordinate system B is expressed as follows:
Q = θ T | O B T T = [ α , β , γ , x , y , z ] T
where x , y , z are the surge, sway, and heave lines of the mobile platform respectively; and α , β , γ are the roll, pitch, and yaw angles of the mobile platform.
Equation (3), which is the IKP’s formula for the GSP, can be used to solve the displacement of i-th actuator using the geometric technique.
L O i = [ L O 1 , L O 2 , L O 3 , L O 4 , L O 5 , L O 6 ] T
L O i = f i Q = | | A R B B i + O B A i | | L l i
where L O i denotes the displacement of the i-th link, L l i indicates the length of i-th link when Q is the initial state, and R is the rotation matrix in the ( P i t c h - R o l l - Y a w ) Euler angle representation, as follows:
R P R Y α , β , γ = c γ s γ 0 s γ c γ 0 0 0 1 c β 0 s β 0 1 0 s β 0 c β 1 0 0 0 c α s α 0 s α c α = c β c γ s α s β c γ c α s γ c α s β c γ + s α s γ c β s γ s α s β s γ + c α s γ c α s β s γ s α c γ s β s α c β c α c β
where c α is c o s α , s α is s i n α , etc.

2.2. FKP Equations

The numerical algorithm’s solution necessitates the construction of a set of nonlinear equations for iteration and root finding. To establish the FKP equations of GSP, IKP’s formula of GSP, Equation (3) is needed. f i Q is the function mapping the pose from Cartesian space to the displacement of the i-th actuator L O i in joint space. The FKP of GSP is to solve corresponding pose Q by giving L O i ; we can construct Equation (5) to form a set of nonlinear equations whose constructed equations are Equation (6).
F i Q = f i Q L n i = 0
f 1 ( Q ) L n 1 = 0 f 2 ( Q ) L n 2 = 0 f 3 ( Q ) L n 3 = 0 f 4 ( Q ) L n 4 = 0 f 5 ( Q ) L n 5 = 0 f 6 ( Q ) L n 6 = 0
where L n i is the input value of the FKP (the displacement of the i-th actuator).

3. Artificial Bee Colony-Based BP Neural Network Algorithm

Artificial neural networks (ANNs) have good nonlinear mapping ability, and can realize the mapping relationship between the displacement of several links and the end-effector pose without considering the intermediate operation process. In the ANN-based IKP method, data were obtained by IKP for sample training. L O i was the input, Q was the output, and only approximate output values could be obtained. The backpropagation neural network (BPNN) is a widely used artificial neural network in GSPs [9].

ABC–BP Neural Network

According to the mapping relation of f { L O 1 , L O 2 , L O 3 , L O 4 , L O 5 , L O 6 } { α , β , γ , x , y , z } , a BPNN with 6 input nodes, 6 output nodes, and 1 hidden layer was designed as shown in Figure 3. Sigmoid function was chosen to be the activation function.
The BPNN model achieved promising performance and flexible network structure. However, it had several deficiencies that prevented it from completing this mission. To optimize the BPNN, the artificial bee colony (ABC) algorithm was used to ensure the stability of the deviation between the predicted and real values of the IKP’s dataset of BPNN training, and to enhance the model training effect, namely, ABC–BPNN [18,19,20,21].
For the BPNN model, the initialization weights and thresholds are given as follows, respectively:
W 1 = 0.0662 1.6832 1.527 1.4254 1.0288 2.0796 0.9240 2.5984 1.9986 1.1251 1.9704 0.8427 2.9220 2.1942 0.7272 0.4587 1.2002 2.6277 1.2651 0.7931 1.6843 1.4514 2.1420 2.4401 2.2850 2.6858 1.3005 1.4514 2.6247 1.6386 2.6616 1.1087 0.6891 1.3788 0.1340 2.3670 2.6722 1.5912 1.3156 2.1011 1.9623 0.4815 1.9344 1.4598 1.9829 2.7022 1.8650 1.4510 1.9723 1.9167 0.1324 2.7276 0.9876 0.6103 2.5931 2.5397 0.0078 0.7973 1.4428 1.8874 B 1 = 0.9841 0.7650 2.2820 2.1350 1.4340 1.5495 0.3450 2.5649 2.2165 0.6414
W 2 = 1.7583 1.4096 2.8489 0.9987 1.8899 0.0096 1.8149 0.7841 1.9333 0.0338 2.6185 1.6147 1.4687 1.8757 2.7148 0.8056 0.9578 1.2417 2.6779 0.0114 1.9383 2.7488 1.1466 0.4589 0.1704 1.2281 0.6174 0.5256 0.8983 1.1637 0.6082 0.7252 0.5100 2.5182 1.6204 1.5583 1.1490 1.1365 2.4286 0.9827 0.9567 1.1117 1.9906 0.0194 2.0536 2.4177 2.2674 0.1703 1.1783 2.2060 1.9097 1.8553 0.2285 0.8113 0.3779 0.7793 1.4021 2.8468 0.5574 1.5143 B 2 = 1.4588 0.9130 1.0489 0.3667 2.6758 1.6079
Due to its benefits of fast convergence and global search, the ABC method is frequently used to solve optimization issues. Bees and food sources are the two most important components of the ABC algorithm. Scout, employed, and onlookers are the three sorts of bees. Scout bees are entrusted to search for food sources at random, while employed and onlooker bees are in charge of nectar mining [22,23]. Numerous studies showed that the ABC algorithm outperforms the genetic algorithm (GA), particle swarm optimization (PSO), and other methods in terms of accuracy and convergence rate [24,25]. In fact, the principle of the ABC algorithm is dealing with the problem of function optimization by simulating the nectar-gathering mechanism of actual bees. The ABC algorithm iterates continuously, compares the advantages and disadvantages of the problem, keeps the good individuals and eliminates the bad ones, and constantly approaches the global optimal solution. The ABC algorithm replaces the solution to the optimal honey of the colony with the solution to the optimal weights and thresholds of the neural network. The optimized BPNN is trained by the global optimal weights and thresholds provided by ABC. The whole ABC–BPNN algorithm is shown in Algorithm A1. The specific steps are as follows:
  • Build a BPNN model.
  • Initialize the parameters of the ABC algorithm: self-variable dimension D, population number N (the number of employed bees is N 1 , the number of onlookers is N 2 , and the number of solutions is N 3 ), maximal cycle number G, and threshold of iteration number for scout bees l i m i t .
    D = N i n p u t × N h i d d e n + N h i d d e n + N h i d d e n × N o u t p u t + N o u t p u t
    N = N 1 + N 2 = 2 N 3
    where N i n p u t is the number of nodes in the input layer, N h i d d e n is the number of nodes in the hidden layer, and N o u t p u t is the number of nodes in the output layer.
  • Employed-bee search. New solution V i ( j ) is generated by employed bees searching the field and is compared with old solution X i ( j ) by using the principle of the greedy algorithm. The strategy compares the size by calculating the fitness value. If the fitness value of the new solution is greater than that of the solution, the solution is replaced by the updated solution. Otherwise, the number of updates is f a i l u r e s + 1. The fitness value is calculated with Equation (10), and V i ( j ) is calculated with Equation (9).
    V i j = X i j + 1 + 2 r a n d 0 , 1 × X i j X r 1 j
    where X i ( j ) is a random selection of other employed bees, different from themselves, r 1 [ 1 , 2 , 3 , , N 3 ] .
    f x i = 1 ( M S E i + 1 ) , M S E i > 0 1 , M S E i < 0
    M S E i = m = 1 n ( y i m y ^ i m ) 2 n
    where M S E i is the mean square error generated by training the i-th solution in the BPNN, y ^ i m indicates the predicted value during training in the BPNN, y i m indicates the actual value, and n indicates the total number of training samples.
    X i t + 1 = V , f ( V ) < f ( X i t ) X i t , f ( V ) f ( X i t )
    where X i t represents the i-th individual in the population of the t generation.
  • Onlookers search. Onlookers calculate possible value P i with Equation (13), and use the roulette to find a new solution among existing ones.
    P i = f x i n = 1 N 3 f x n
  • Scout-bee search. The rapid convergence of employed and scout bees may lead to a decrease in the overall diversity of the population. In order to avoid the population entering the local optimum, the search mechanism of scout bees was designed on the basis of the ABC algorithm. If the number of update f a i l u r e s exceeds l i m i t , the solution is discarded and replaced by a new solution generated by Equation (14), and the number of update f a i l u r e s is initialized to zero. In this paper, the value of l i m i t is the product of N 3 and D.
    X i = X m i n + r a n d 0 , 1 X m a x X m i n
  • If the current cycle number is greater than maximal cycle number G, Step 3 is repeated. Otherwise, the solution with the maximal fitness is output at the end of the training.
  • According to the optimal solution provided by the ABC algorithm, the initial weights and thresholds of the BPNN are obtained. Subsequently, the ABC–BPNN model is trained and tested with the sample data to achieve the pose prediction of GSP.

4. Analysis and Design of the Numerical Algorithm

4.1. Newton–Raphson Algorithm

In the traditional hybrid algorithm (BPNN and numerical algorithm), Newton–Raphson is used as the main method for numerical solutions. Some other improved Newtonian methods are used for the numerical iteration of optimization algorithms, as shown in Figure 4.
  • Newton–Raphson method:
    The formula of the NR method for solving nonlinear equations of FKP is:
    Q n + 1 = Q n J 1 Q n F ( Q n ) ( n = 0 , 1 , 2 , 3 )
    where J is a Jacobian matrix, and its formula is:
    J = F 1 α 1 F 1 z 1 F 6 α 6 F 6 z 6
  • Newton downhill method:
    The formula for the Newton downhill (NR-dh) method for solving nonlinear equations of FKP is:
    Q n + 1 = Q n λ J 1 Q n F ( Q n ) ( 0 < λ 1 )
    where λ is the descent factor; when λ = 1 , it is the NR method.
    When | | F ( Q n + 1 ) | | < | | F ( Q n ) | | , λ remains the same. On the other hand, λ = 2 t , ( t = 0 , 1 , 2 ) .

4.2. Improved Newton’s Method for Nonlinear Singular Equations

Neither the traditional nor the above method can solve the singular Jacobian matrix of FKP nonlinear equations. According to Equation (15), a new set of J is formed continuously in the process of the solving iteration, and its inverse is required. In the process of iteration, when J forms a singular matrix, R a n k J < 6 , its inverse cannot be solved. Therefore, the general solution formula of NR method should be:
Q n + 1 = Q n J + Q n F ( Q n ) ( n = 0 , 1 , 2 , 3 )
where continuous iterating pseudoinverse matrix J + slows down the solution process, affects the overall efficiency, and cannot guarantee accuracy of computation. To solve these problems, any value that is input into the feasible motion space of the mechanism can have a solution. Therefore, an improved Newton’s method for solving nonlinear singular equations was introduced [15]. Lv et al. [15] combined the methods that were proposed in Kou et al. [26], and Howk et al. [27]; a diagonal matrix containing parameters was added to the singular Jacobian matrix to change the irreversible characteristics of the Jacobian matrix in the iterative process, and the convergence order of this new singular algorithm was second. The equation proposed in Kou et al. [26] is as follows:
Q n + 1 = Q n d i a g μ i ( n ) F Q n + J 1 F Q n
where μ i n R { 0 } . when J is for the singular matrix, the d i a g μ i ( n ) F Q n join can solve this problem.
The formula of the improved Newton’s method for nonlinear singular equations is: when n = 0 , the formula is:
Q 0 * = Q 0 , Q 1 = Q 0 [ d i a g ( μ i ( 0 ) F ( Q 0 ) ) + F ( γ ( Q 0 ) + ( 1 γ ) Q 0 * ) ] 1 F ( Q 0 )
when n 1 , the formula is:
Q n * = Q n d i a g μ i n F Q n + F γ Q n 1 + 1 γ Q n 1 * 1 F Q n , Q n + 1 = Q n d i a g λ i n F Q n + F γ Q n + 1 γ Q n * 1 F Q n
where, when γ = 1 2 , it is the QMn-M algorithm. When γ = 0 , it is the PC-M algorithm. When γ = 1 , the two-step iterative Equations (20) and (21) change into the single-step iterative Equation (19), which is Newton’s improvement on the standard.
The recommended algorithm is the QMn-M algorithm at γ = 1 2 , which performed better on the FKP of GSP, with better iterations and total running time than those of the others. A comparison of several algorithms is shown in Table 1.

4.3. Simplified Newton Iteration to Optimize QMn-M Algorithm

The QMn-M algorithm solves singular Jacobian matrix J and reduces its problem-solving speed. To ensure the global performance, and its operation speed and accuracy, we used the simplified Newton iteration (SNR) method to optimize the QMn-M algorithm.
Simplified Newton Iteration:
Q n + 1 = Q n C F Q n , C = J 1 Q ε
where C is a constant Jacobian matrix. When it is not satisfied:
| | F ( Q n + 1 ) | | < | | F ( Q n ) | |
to renew the Jacobian matrix.
The QMn-M and SNR algorithm can effectively improve the time efficiency of the algorithm and guarantee the accuracy of the value, as shown in Figure 5. Compared with the traditional hybrid algorithm, it can solve the global pose problem.

4.4. FKP of Real-Time Control Improvement

In the control of a 6-DOF parallel robot, a real-time solution of FKP is more practical. The control cycle and sampling interval are usually milliseconds. Therefore, the solution of FKP connected between control cycles is approximate. According to the deviation-driven algorithm on real-time FKP [12], and by Equation (24), Q p r e (the value of the last solution) is reused, and ABC–BPNN calls are reduced. If the formula is satisfied, Q p r e is used to directly carry out a simplified Newton iteration. Otherwise, ABC–BPNN is called to give an approximation.
Δ L m a x = m a x | f i ( Q p r e ) L n i |
Δ L m a x < ε 0
where ε 0 is the length error threshold that controls whether to call ANNs. The whole hybrid algorithm is shown in Figure 6 and Algorithm A2.

5. Experiment

The experimental process can be divided into three parts:
  • Part 1: Inverse kinematics solution. The corresponding data are obtained to form the dataset and normalized.
  • Part 2: Training for neural networks. Test samples are input into the trained model for pose prediction.
  • Part 3: Numerical iteration. Predicted results are input as the numerical algorithm’s initial point to acquire the precise output.
Several experiments were conducted on the GSP (6-UCU) as shown in Figure 1. The positions of hinge points are given in Table 2. The maximal iterations N m a x were set to 20, and the permissible error was 10 4 mm. The following experiments were carried out in the environment of MATLAB R2019b, and the operating system was Windows 10. When Q = [ 0 , 0 , 0 , 0 , 0 , 0 ] T , the initial value of each links variable was: L i = [ 1306.7130 , 1306.7130 , 1306.7130 , 1306.7130 , 1306.7130 , 1306.7130 ] T ; the unit is millimeters.

5.1. Data Acquisition

A specific number of poses inside the workspace should be chosen before the training process, and the associated actuator displacements should be acquired by solving IKP with the corresponding actuator displacement Equation (3). The sample sets for training ANNs are formed by combining the two groups of data and then reversing their mappings. Essentially, ANNs use calculated data in a joint space as inputs, and corresponding pose data in Cartesian space as predicted outputs.

5.2. Neural Network Experiment

To train the ANNs, the network/data management toolbox in MATLAB R2019b was used. In the neural network comparison experiment, 300 groups of continuous data were collected from the machine. We divided the dataset at a ratio of 7:3. The training set consisted of 210 groups, and the test set consisted of 90 groups. We introduced a genetic algorithm–backpropagation neural network (GA-BPNN) to compare with our ABC–BPNN and the traditional BPNN. The BPNN, GA–BPNN, and ABC–BPNN parameter settings were the same, where the learning rate was 0.001, and set epochs were 200. In this experiment, the three neural network models were compared through metrics, as shown in Table 3. The average error of each variable predicted by the neural network model is given in Table 4. In this paper, we calculated the error through the numerical deviation of the corresponding data. The error calculation equation used is as follows:
E r r o r = | Q i ^ Q i | , ( i = 1 , 2 , 3 , , 6 )
A v e r a g e E r r o r = 1 n m = 1 n | Q ^ m i Q m i | , ( i = 1 , 2 , 3 , , 6 )
where Q i ^ represents the predicted value of a pose variable, Q i represents the real value of a pose variable, and m represents the individual number of the same variable in Q ^ m i .
Figure 7 shows the predicted values of the three models in a test set. A group of data were selected for comparison, and the pose was the predicted value of the neural network. The experimental results in the figure demonstrate that ABC–BPNN had a better prediction ability than that of the traditional BPNN or GA–BPNN. Figure 8 compares the error of the surge(x) predicted value of the neural network models with 10 groups of sample data. the error calculation of the surge variable was performed with Equation (26). Through the optimized neural network, its error value obviously decreased, as shown in the figure. By using a heuristic algorithm, the network model’s prediction performance was enhanced, and ABC–BPNN was more able to adjust to changes in the process.
According to the metrics given in Table 3, the ABC algorithm optimized the initialization weights well, which improved the prediction ability of the BPNN model. Compared with GA–BPNN and BPNN, the RMSE index of ABC–BPNN decreased by 42.1% and 31.4%, respectively, and the R 2 performance of ABC–BPNN improved by 11.0% and 5.6%, respectively. The average error of the three models is given in Table 4; the maximal improvement of ABC–BPNN error optimization was 46.3%. By comparing the average error, the ABC algorithm could reduce the average error of various variables, and its effect was better than that of the genetic algorithm. Experimental results show that ABC–BPNN could reduce the dependence on the dataset and the prediction error of the neural network.

5.3. Numerical Algorithm Experiment

We used the data obtained by the neural network to conduct experiments in MATLAB R2019b. On a PC with a 2.30 GHz processor and 8 GB RAM, the FKP that corresponded to the obtained data was solved. An error threshold ε 2 was used to control the QMn-M algorithm in the experiment, and an error threshold ε 1 was subsequently used to control the SNR algorithm. The number of iterations and overall operation time fluctuate depending on ε 1 . The design of the error threshold can be changed with specific data until the value that renders it the most efficient is found. Error threshold ε 1 is used to govern the end of the SNR algorithm and the entire process. Its value is generally accurate to four decimal places (as shown in Table 5, The precise level was 10 4 ).
After the neural network experiment, the predicted values were iterated numerically. In this section, the average numbers of iterations, required operation time, and different iterative methods are compared. Table 5 shows the comparison of seven iteration methods, giving the average number of iterations and the required time. As shown in Table 5, the required time and average number of iterations of the proposed QMn-M and SNR were reduced, and its performance was better than that of the same second-order NR algorithm after being optimized by SNR. In Table 6, the traditional NR, and NR-dh with QMn-M and PC-M are compared. QMn-M and PC-M could solve nonlinear singular equations, and the advantages of this algorithm in solving the forward kinematics problem are demonstrated. Experiments showed the feasibility of QMn-M and PC-M in solving singular matrix data. ( μ i n , λ i n ) about Q n * and Q n + 1 in Equation (21) were set to be the same parameters. In the QMn-M experiment, different ( μ i n , λ i n ) values caused different levels of performance, and unsuitable ( μ i n , λ i n ) values may render it divergent and unsolvable. Figure 9 shows the comparative experiment of the operation time required by four algorithms in 10 groups of data. As described in the Figure 9, QMn-M and Newton–Raphson had the best performance, followed by PC-M, and NR-dh had the worst performance. Figure 10 is a comparison of QMn-M, QMn-M and SNR, and the traditional NR method. It shows that SNR combined with a numerical algorithm could greatly improve the efficiency of the algorithm and better guarantee accuracy.
Furthermore, we found the percentage improvement performance of other iterative algorithms by comparing with QMn-M and SNR, which is illustrated in Table 7. Compared to NR-hd, the maximal percentage improvement in performance for the average number of iterations and required time was 68.8% and 70.60%, respectively. Compared to NR, the minimal percentage improvement in performance for the average number of iterations and required time was 14.4% and 13.9%, respectively.

6. Conclusions

This paper mainly optimized the traditional hybrid algorithm for FKP. The ABC–BPNN model was used to train the IKP’s value to obtain a good initial value, and the QMn-M and SNR algorithm was used to iteratively calculate the excellent initial value. The comparison chart in the numerical algorithm experiment shows that the QMn-M and SNR algorithm was superior to other methods in terms of iterations and operation time. It also has the ability to calculate a singular matrix. For continuous samples, its solution does not need to continuously call ABC–BPNN, which greatly reduces the overall operation time required, and makes it convenient to solve on the real-time platform. This new hybrid algorithm can not only ensure that the GSP can have solutions in feasible space, but also meet the speed and accuracy of real-time computation. This algorithm also has portability, which is beneficial to solve the FKP for different structural platforms.

Author Contributions

Conceptualization, H.Z. and W.X.; methodology, H.Z. and W.X.; software, H.Z.; validation, B.Y., F.D., L.C. and J.H.; data curation, H.Z. and B.Y.; writing—original draft preparation, H.Z.; writing—review and editing, W.X., B.Y., F.D., L.C. and J.H.; visualization, B.Y. and F.D.; supervision, L.C. and J.H. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by National Natural Science Foundation Youth Fund of China, grant number 61803286.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data presented in this study are available on request from the corresponding author. The data are not publicly available due to privacy.

Conflicts of Interest

The authors declare no conflict of interest.

Appendix A

The whole ABC–BPNN algorithm for the pose estimation of Gough–Stewart platforms is as follows.
Algorithm A1 ABC–BP neural network for FKP.
  • Input: The displacement of current GSP, L O i ;
  • Output: The pose of current end-effector Q p r e d i c t i o n .
1:
Establish BP neural network model.
2:
Initialize the parameters of the ABC algorithm.
3:
Employed bees generate candidate solution V i ( j ) , V i ( j ) shown in Equation (9).
4:
Fitness value comparison in Equations (10) and (12). If N e w > O l d , then O l d N e w , else f a i l u r e s + 1 .
5:
Compute the possible value P i of the solution, shown in (13), search according to P i to generate new solutions.
6:
Fitness value comparison in Equations (10) and (12). If N e w > O l d then O l d N e w , else f a i l u r e s + 1 ;
7:
If f a i l u r e s > l i m i t , then scout bees initial solution, shown in Equation (14); else, move to Step 8.
8:
If c u r r e n t c y c l e s > G , then save the optimal fitness value; else, move to Step 3.
9:
Get the optimal weights and thresholds and train the BP neural network.
The whole hybrid algorithm to solve forward kinematics problem for Gough–Stewart platforms is as follows.
Algorithm A2 Hybrid algorithm for forward kinematics problem of 6-DOF.
  • Input: Coordinate vectors of lower and uppers joints with respect to their own coordinate frames: b 1 , b 2 , , b 6 ; a 1 , a 2 , , a 6 . The displacement of current GSP: L O i . Error thresholds: ε 1 , ε 2 . Length error threshold: ε 0 . Max iterations: N m a x .
  • Output: The pose of current moving coordinate platform: α , β , γ , x , y , z .
1:
if Q i = N U L L & & Δ L m a x > ε 0  then
2:
    Q i A B C - B P N N ( L O i ) ;
3:
   while  Δ E 2 > ε 2  do
4:
      Q i E q 21 ( Q i ) ;
5:
      C R e n e w ( C ) ;
6:
     while  Δ E 1 > ε 1 & & N < N m a x  do
7:
        if  | | F ( Q n + 1 ) | | < | | F ( Q n ) | |  then
8:
           Q i E q 22 ( Q i ) ;
9:
        else
10:
           Q i E q 15 ( Q i ) ;
11:
        end if
12:
         N = N + 1 ;
13:
     end while
14:
      r e t u r n Q f i n a l ;
15:
   end while
16:
else
17:
    s t e p 6 s t e p 15 ;
18:
end if

References

  1. Merlet, J.P. Parallel Robots, 2nd ed.; Springer: Dordrecht, The Netherlands, 2006; pp. 77–78. [Google Scholar]
  2. Wang, Q.; Su, J.; Lv, Z.; Zhang, L.; Lin, H.; Xu, G. Efficient hybrid method for forward kinematics analysis of parallel robots based on signal decomposition and reconstruction. Adv. Mech. Eng. 2017, 9, 1687814017699094. [Google Scholar] [CrossRef] [Green Version]
  3. Sadjadian, H.; Taghirad, H.D. Numerical methods for computing the forward kinematics of a redundant parallel manipulator. In Proceedings of the IEEE Conference on Mechatronics and Robotics, Germany, Aachen, 13–15 September 2004; pp. 557–562. [Google Scholar]
  4. Li, Y.; Xu, Q. Kinematic analysis of a 3-PRS parallel manipulator. Robot. Comput. Integr. Manuf. 2007, 23, 395–408. [Google Scholar] [CrossRef]
  5. Merlet, J.-P. Solving the forward kinematics of a Gough-type parallel manipulator with interval analysis. Int. J. Robot. Res. 2004, 23, 221–235. [Google Scholar] [CrossRef]
  6. Gan, D.; Liao, Q.; Dai, J.S.; Wei, S.; Seneviratne, L.D. Forward displacement analysis of the general 6–6 Stewart mechanism using Gröbner bases. Mech. Mach. Theory 2009, 44, 1640–1647. [Google Scholar] [CrossRef]
  7. Chen, S.-H.; Fu, L.-C. The forward kinematics of the 6-6 Stewart platform using extra sensors. In Proceedings of the 2006 IEEE International Conference on Systems, Man and Cybernetics, Taipei, China, 8–11 October 2006; Volume 6, pp. 4671–4676. [Google Scholar]
  8. Morell, A.; Tarokh, M.; Acosta, L. Solving the forward kinematics problem in parallel robots using Support Vector Regression. Eng. Appl. Artif. Intell. 2013, 26, 1698–1706. [Google Scholar] [CrossRef]
  9. Parikh, P.J.; Lam, S.S.Y. A hybrid strategy to solve the forward kinematics problem in parallel manipulators. IEEE Trans. Robot. 2005, 21, 18–25. [Google Scholar] [CrossRef]
  10. Parikh, P.J.; Lam, S.S. Solving the forward kinematics problem in parallel manipulators using an iterative artificial neural network strategy. Int. J. Adv. Manuf. Technol. 2009, 40, 595–606. [Google Scholar] [CrossRef]
  11. Kardan, I.; Akbarzadeh, A. An improved hybrid method for forward kinematics analysis of parallel robots. Adv. Robot. 2015, 29, 401–411. [Google Scholar] [CrossRef]
  12. Zhu, Q.; Zhang, Z. An efficient numerical method for forward kinematics of parallel robots. IEEE Access 2019, 7, 128758–128766. [Google Scholar] [CrossRef]
  13. Zhu, Q.; Zhang, Z.; Ji, X. General approach for real-time forward kinematics solution of Stewart platform. J. Harbin Eng. Univ. 2021, 42, 394–399. (In Chinese) [Google Scholar]
  14. López, E.G.; Yu, W.; Li, X. Optimum design of a parallel robot using neuro-genetic algorithm. J. Mech. Sci. Technol. 2021, 35, 293–305. [Google Scholar] [CrossRef]
  15. Lv, W.; Wei, L.T.; Feng, E.M. A modification of Newton’s method solving non-linear equations with singular Jacobian. Kongzhi Juece Control Decis. 2017, 32, 2240–2246. [Google Scholar]
  16. Karaboga, D.; Basturk, B. A powerful and efficient algorithm for numerical function optimization: Artificial bee colony (ABC) algorithm. J. Glob. Optim. 2007, 39, 459–471. [Google Scholar] [CrossRef]
  17. Yang, C.; He, J.; Han, J.; Liu, X. Real-time state estimation for spatial six-degree-of-freedom linearly actuated parallel robots. Mechatronics 2009, 19, 1026–1033. [Google Scholar] [CrossRef]
  18. Xu, Q.; Chen, J.; Liu, X.; Li, J.; Yuan, C. An ABC-BP-ANN algorithm for semi-active control for Magnetorheological damper. KSCE J. Civ. Eng. 2017, 21, 2310–2321. [Google Scholar] [CrossRef]
  19. Cui, L.; Zhang, K.; Li, G.; Wang, X.; Yang, S.; Ming, Z.; Huang, J.Z.; Lu, N. A smart artificial bee colony algorithm with distance-fitness-based neighbor search and its application. Future Gener. Comput. Syst. 2018, 89, 478–493. [Google Scholar] [CrossRef]
  20. Chen, S.; Fang, G.; Huang, X.; Zhang, Y. Water quality prediction model of a water diversion project based on the improved artificial bee colony–backpropagation neural network. Water 2018, 10, 806. [Google Scholar] [CrossRef] [Green Version]
  21. Li, H.; Lu, Y.; Zheng, C.; Yang, M.; Li, S. Groundwater level prediction for the arid oasis of Northwest China based on the artificial bee colony algorithm and a back-propagation neural network with double hidden layers. Water 2019, 11, 860. [Google Scholar] [CrossRef] [Green Version]
  22. Karaboga, D.; Akay, B. A comparative study of artificial bee colony algorithm. Appl. Math. Comput. 2009, 214, 108–132. [Google Scholar] [CrossRef]
  23. Karaboga, D.; Ozturk, C. A novel clustering approach: Artificial Bee Colony (ABC) algorithm. Appl. Soft Comput. 2011, 11, 652–657. [Google Scholar] [CrossRef]
  24. Karaboga, D.; Basturk, B. On the performance of artificial bee colony (ABC) algorithm. Appl. Math. Comput. 2008, 8, 687–697. [Google Scholar] [CrossRef]
  25. Karaboga, D.; Gorkemli, B.; Ozturk, C.; Karaboga, N. A comprehensive survey: Artificial bee colony (ABC) algorithm and applications. Artif. Intell. Rev. 2014, 42, 21–57. [Google Scholar] [CrossRef]
  26. Kou, J.; Li, Y.; Wang, X. Efficient continuation Newton-like method for solving systems of non-linear equations. Appl. Math. Comput. 2006, 174, 846–853. [Google Scholar] [CrossRef]
  27. Howk, C.L. A class of efficient quadrature-based predictor–corrector methods for solving nonlinear systems. Appl. Math. Comput. 2016, 276, 394–406. [Google Scholar] [CrossRef]
Figure 1. Example of a 6-UCU GSP.
Figure 1. Example of a 6-UCU GSP.
Sensors 22 05318 g001
Figure 2. Schematic of 6-UCU GSP. (a) Schematic of the universal joint positions; (b) 6–6 GSP model and coordinate systems.
Figure 2. Schematic of 6-UCU GSP. (a) Schematic of the universal joint positions; (b) 6–6 GSP model and coordinate systems.
Sensors 22 05318 g002
Figure 3. Structure of the BP neural network.
Figure 3. Structure of the BP neural network.
Sensors 22 05318 g003
Figure 4. Traditional hybrid algorithm.
Figure 4. Traditional hybrid algorithm.
Sensors 22 05318 g004
Figure 5. QMn-M and SNR algorithm.
Figure 5. QMn-M and SNR algorithm.
Sensors 22 05318 g005
Figure 6. Algorithm for forward kinematics problem of 6-DOF. Δ E 1 refers to the difference between Q n + 1 and Q n of each iteration, and ε 1 is the threshold for controlling the end of the iteration.
Figure 6. Algorithm for forward kinematics problem of 6-DOF. Δ E 1 refers to the difference between Q n + 1 and Q n of each iteration, and ε 1 is the threshold for controlling the end of the iteration.
Sensors 22 05318 g006
Figure 7. Predicted and real values of ANN model.
Figure 7. Predicted and real values of ANN model.
Sensors 22 05318 g007
Figure 8. Predicted error value of surge(x).
Figure 8. Predicted error value of surge(x).
Sensors 22 05318 g008
Figure 9. Comparison of algorithm operation time.
Figure 9. Comparison of algorithm operation time.
Sensors 22 05318 g009
Figure 10. Comparison of algorithm operation time for QMn-M and SNR.
Figure 10. Comparison of algorithm operation time for QMn-M and SNR.
Sensors 22 05318 g010
Table 1. Analysis of the advantages and disadvantages of several numerical algorithms.
Table 1. Analysis of the advantages and disadvantages of several numerical algorithms.
Numerical AlgorithmsAdvantagesDisadvantages
Newton–RaphsonEasy to implement and fast convergence.Sensitive to initial value, and the iteration is easy to diverge.
Newton downhillReduces sensitivity to initial values.The strong coupling of the Jacobian matrix reduces the iteration speed in FKP equations.
QMn-M or PC-MIt can solve the nonlinear equations of a singular Jacobian matrix, and only two function values need to be calculated in each iteration step 1.The amount of matrix calculation is increased, and more parameter settings are added.
1 With the QMn-M or PC-M algorithm, only two function values need to be calculated in each iteration step because, in Equation (21), F ( γ Q n 1 + ( 1 γ ) Q n 1 * ) in the last iteration formula is in Equation (21). The only need is to calculate two functions: F ( γ Q n 1 + ( 1 γ ) Q n 1 * ) .
Table 2. Position of hinge points.
Table 2. Position of hinge points.
Hinge Point Numbers 1 (mm)
123456
X A −250.0250.01350.01100.0−1100.0−1350.0
Y A 1414.51414.5−490.7−923.7923.7−490.7
Z A 0.00.00.00.00.00.0
X B −525.0525.0625.0100.0−100.0−625.0
Y B 418.5418.5245.3−663.9−663.9245.3
Z B 0.00.00.00.00.00.0
1 (XA, YA, ZA) is the value of base coordinate system {A}. (XB, YB, ZB) is the value of moving coordinate system {B}.
Table 3. Comparison of four metrics.
Table 3. Comparison of four metrics.
Model Name
BPGA-BPABC-BP
T r a i n _ R 2 0.79970.84940.8972
T e s t _ R 2 0.79610.83770.8945
T r a i n _ M A E 4.35413.36942.8674
T e s t _ M A E 4.55433.40012.8784
T r a i n _ R M S E 5.73244.85463.3291
T e s t _ R M S E 5.80244.89163.3548
T r a i n _ M A P E 11.8970%9.5493%7.9761%
T e s t _ M A P E 12.0483%9.6759%7.9801%
Table 4. Average error of neural network model.
Table 4. Average error of neural network model.
Average Error of BPAverage Error of GA–BPAverage Error of ABC–BP
Surge (mm)4.253.152.88
Sway (mm)4.543.452.63
Heave (mm)4.683.672.51
Roll (°)3.492.962.77
Pitch (°)3.552.942.93
Yaw (°)3.583.012.84
Table 5. Performance comparison of methods.
Table 5. Performance comparison of methods.
IN 1/IN1 2Time (ms)
Newton–Raphson3.345/03.069
Newton downhill9.177/08.997
QMn-M3.447/03.151
PC-M4.015/03.934
NR-dh and SNR5.354/3.1734.522
QMn-M and SNR2.862/1.0592.641
PC-M and SNR3.409/1.1373.218
1 IN represents the total number of iterations. 2 IN1 represents the number of simplified Newton iterations.
Table 6. Comparison of numerical algorithms to solve a singular matrix.
Table 6. Comparison of numerical algorithms to solve a singular matrix.
μ i n , λ i n InputOutput
Newton–Raphson(NULL, NULL) ( 102.9 , 51.5 , , 16.6 ) T Failure
Newton downhill(NULL, NULL) ( 102.9 , 51.5 , , 16.6 ) T Failure
QMn-M ( 0.1 , 0.1 ) ( 102.9 , 51.5 , , 16.6 ) T ( 101.7 , 50.3 , , 15.4 ) T
PC-M ( 0.1 , 0.1 ) ( 102.9 , 51.5 , , 16.6 ) T ( 101.7 , 50.3 , , 15.4 ) T
Newton–Raphson(NULL, NULL) ( 97.3 , 47.2 , , 14.6 ) T Failure
Newton downhill(NULL, NULL) ( 97.3 , 47.2 , , 14.6 ) T Failure
QMn-M ( 0.1 , 0.1 ) ( 97.3 , 47.2 , , 14.6 ) T ( 95.2 , 46.7 , , 14.3 ) T
PC-M ( 0.1 , 0.1 ) ( 97.3 , 47.2 , , 14.6 ) T ( 95.2 , 46.7 , , 14.3 ) T
Newton–Raphson(NULL, NULL) ( 104.9 , 50.4 , , 18.1 ) T Failure
Newton downhill(NULL, NULL) ( 104.9 , 50.4 , , 18.1 ) T Failure
QMn-M ( 0.01 , 0.1 ) ( 104.9 , 50.4 , , 18.1 ) T ( 103.2 , 50.1 , , 16.1 ) T
PC-M ( 0.01 , 0.1 ) ( 104.9 , 50.4 , , 18.1 ) T ( 103.2 , 50.1 , , 16.1 ) T
Table 7. Improvement percentages of the proposed method.
Table 7. Improvement percentages of the proposed method.
QMn-M and SNRAverage Number of IterationsRequired Time
Over Others% of Improvement% of Improvement
Newton–Raphson14.413.9
Newton downhill68.870.6
QMn-M16.915.2
PC-M28.732.8
NR-dh and SNR46.541.5
PC-M and SNR16.017.9
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Zhu, H.; Xu, W.; Yu, B.; Ding, F.; Cheng, L.; Huang, J. A Novel Hybrid Algorithm for the Forward Kinematics Problem of 6 DOF Based on Neural Networks. Sensors 2022, 22, 5318. https://doi.org/10.3390/s22145318

AMA Style

Zhu H, Xu W, Yu B, Ding F, Cheng L, Huang J. A Novel Hybrid Algorithm for the Forward Kinematics Problem of 6 DOF Based on Neural Networks. Sensors. 2022; 22(14):5318. https://doi.org/10.3390/s22145318

Chicago/Turabian Style

Zhu, Huizhi, Wenxia Xu, Baocheng Yu, Feng Ding, Lei Cheng, and Jian Huang. 2022. "A Novel Hybrid Algorithm for the Forward Kinematics Problem of 6 DOF Based on Neural Networks" Sensors 22, no. 14: 5318. https://doi.org/10.3390/s22145318

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