Abstract

Based on the established serial 6-DOF robot calibration experiment platform, this paper aims to analyze and compare the effects of four error compensation methods, which are pseudotarget iteration-based error compensation method with three different forms and the Newton–Raphson-based error compensation method. Firstly, the pose error model of the serial robot is established based on the M-DH model in this paper. The calibration results show that the accuracy of the Staubli TX60 robot has been greatly improved. The average comprehensive position accuracy is increased by 88.7%, and the average comprehensive attitude accuracy is increased by 56.6%. Secondly, the principles of the four error compensation methods are discussed, and the effectiveness of the four error compensation methods are compared through experiments. The results show that the four error compensation methods can achieve error compensation well. The compensation accuracy is consistent with the identification accuracy of the kinematic model. The pseudotarget iteration with differential form has the best performance by the comprehensive consideration of accuracy and computational efficiency. Error compensation determines whether the accuracy of the identified model can be achieved. This paper presents a systematic experimental validation research on the effectiveness of four error compensation methods, which provides a reliable reference for the kinematic error compensation of industrial robots.

1. Introduction

The high-end manufacturing application of industrial robots has attracted extensive attention from research institutions [14]. In 2017–2019, the National Key Research and Development Project “Intelligent robot” of China pointed out that the position and attitude accuracy should be better than 0.1 mm and 0.1°, respectively, in the high-end manufacturing field. However, the repeated positioning accuracy of industrial robots can reach 0.01 mm. The absolute positioning accuracy still cannot meet the accuracy requirements of the high-end manufacturing field. At present, the absolute positioning accuracy of serial industrial robots is in centimeter level [5, 6].

The absolute positioning accuracy of industrial robots can be improved from three aspects, which are precision design, advanced control method, and error calibration. The precision design is mainly for the design, manufacture, and assembly of industrial robots. High-accuracy tracking control can be achieved by designing an advanced control method [79]. However, accurate model parameters can further improve the performance of the high-accuracy control method. The error calibration is mainly used in the robot application field, which is a common method to improve the accuracy of industrial robots [10, 11]. The positioning error of the robot is caused by the coupling of multiple error factors, such as joint errors, kinematic error, and nonkinematic error [12, 13]. The kinematic error is the main error factor that affects the positioning accuracy of industrial robots. The kinematic error accounts for more than 80% of the total error [14]. The kinematic calibration methods are mainly divided into error model-based method and axis measurement method [15, 16]. The positioning accuracy of the Staubli RX160L robot was improved from 1.41 mm to 0.15 mm based on the error model method [17]. The positioning accuracy of the ABB IRB1600 robot was improved from 0.968 mm to 0.364 mm based on the axial measurement method [18]. The kinematic parameters obtained through the axis measurement method are consistent with the mechanical configuration. Compared with the axis measurement method, the error model method has better calibration accuracy.

The calibration process of the error model-based method includes four key steps, i.e., error modeling, error measurement, parameter identification, and error compensation. The established error models are divided into the position error model, the pose error model, and the distance error model [19]. The position/pose error model-based calibration needs to perform the coordinate transformation. The error of coordinate transformation will result in bad calibration performance [20]. The distance error model does not need to perform the coordinate transformation. However, the performance of distance error model-based calibration is worse. Compared with the other two models, the pose error model comprehensively describes the position and attitude errors of industrial robots. The kinematic model of the robots also has effects on the calibration performance. Denavit and Hartenberg proposed the DH kinematic model that is commonly applied by the industrial robot manufacturer [21]. The error model based on the DH model has the singularity problem when the two neighboring joint axes are parallel or near parallel. Several novel kinematic models have been proposed for robot calibration, such as the complete and parametrically continuous (CPC) model [22], the zero reference (ZR) model [23], and the product of exponential (POE) model [24]. The measuring equipment commonly used are laser tracker [18], ball bar [25], visual measurement [26], and so on. The laser tracker is the most widely used measuring equipment for robot calibration. At present, many researches on the first three steps have been conducted. Error compensation is the last step that determines whether the accuracy of the identified model can be achieved.

The direct error compensation method is to replace the kinematic parameters of the robot controller. Piper criterion presents that three adjacent joint axes intersect at a point or three adjacent joint axes are parallel to each other. However, the kinematic parameters obtained through identification no longer satisfy the Piper criterion [27]. The closed solution of the inverse kinematic solution cannot be solved. Moreover, the controllers of most industrial robots adopt a closed structure. It is impossible to modify the kinematic parameters in the controller directly. There are two methods to implement the kinematic error compensation, such as the pseudotarget iteration-based error compensation method [28] and the Newton–Raphson-based error compensation method [29]. Veitschegger and Wu improved the error compensation method based on pseudotarget iteration [30]. According to the literature research results, there are few experimental comparative verification studies on the effectiveness of these error compensation methods.

In this paper, the experimental analysis on the effectiveness of kinematic error compensation methods for serial industrial robots is presented. The pose error model of the industrial robot established based on the M-DH model is given in Section 2. The kinematic calibration of the Staubli TX60 robot has been implemented. Section 3 presents the principle of four different error compensation methods. And the effectiveness of error compensation methods has been compared. The conclusion and future work are given in Section 4.

2. M-DH Kinematic Model

2.1. Pose Error Model Based on the M-DH Model

The most commonly used kinematic model of industrial robots is the DH model. The error model based on the DH model has singularity when the two neighboring joint axes are parallel or near parallel. To overcome this problem, Hayati and Mirmirani proposed the M-DH model [31]. The M-DH kinematic model adds an angle parameter β to describe the kinematic relationship between the neighboring parallel axes. According to the M-DH model, the transformation relationship between the neighboring coordinate frames of the robot is obtained as follows:where ai, di, αi, θi, and βi (i = 1, 2, …, 6) are the nominal values of the link length, link offset, link twist angle, joint angle, and joint torsion angle of the i-th joint, respectively. s and c represent the abbreviations of sin and cos, respectively.

As shown in Figure 1, the coordinate frames of the Staubli TX60 robot based on the M-DH kinematic model are presented. The base frame and the tool frame are, respectively, coincidence to T1 and T6. The pose of the robot end can be obtained by equation (2). The nominal M-DH parameters of the Staubli TX60 robot are shown in Table 1.where n, o, and a are the column vectors of the rotation matrix R and P is the position vector.

The end pose error of the robot is defined as ΔT, which is the difference between the actual pose TR and the theoretical pose TN. It is expressed as follows:where Δn, Δo, and Δa are errors of the column vectors of the rotation matrix R.

The partial derivatives of the pose error with the nominal kinematic parameters are given in the following equation, where the high-order terms are ignored:where Δηi = [Δθi Δdi Δai Δαi Δβi] is the parameter error of the M-DH model to be identified.

Equation (4) is rewritten in a matrix form as follows:where and .

2.2. Redundancy Analysis of the Pose Error Model

When the column vectors of the Jacobian matrix H are linearly dependent, the identification accuracy of the parameters will be poor. Therefore, it is necessary to analyze and remove the redundant parameters from the pose error model. QR decomposition is commonly applied to redundancy analysis. The values on the diagonal of the R matrix obtained by the QR decomposition of the Jacobian matrix H in equation (5) are shown in Table 2. The kinematic parameters with a value of zero on the diagonal of the matrix R are redundant. In some cases, the kinematic parameters with smaller values on the diagonal of the matrix R also can be removed. As shown in Table 2, when the base frame and the tool frame are not considered, there are no redundant parameters of the pose error model based on the M-DH model.

2.3. Kinematic Parameter Identification

The industrial robot calibration system built in this paper is shown in Figure 2. The laser tracker Leica AT960 is adopted in the calibration system. The measurement uncertainty of the laser tracker is ±(15 μm + 6 μm/m). The industrial robot to be calibrated is Staubli TX60. The repeated positioning accuracy of the robot is ±0.02 mm, and the nominal load is 3 kg. The T-MAC tool of the laser tracker is installed on the flange of the Staubli TX60 robot. The measurement processes involved in this paper are in compliance with the industrial robot performance specifications and test method standards GB/T-12642-2013 [32] and ISO-9283 [33].

In this paper, the Levenberg–Marquardt (LM) optimization algorithm is used to identify the kinematic errors. The LM optimization algorithm has advantages of fast convergence and good stability for solving nonlinear equations [34]. The iterative recursive formula of the LM algorithm is given as follows:where f = ΔE − HΔη, μ is the damping parameter, and J is the Jacobian matrix of the function f.

The base frame of the Staubli TX60 robot is defined as the reference frame. In the experiment, fifty poses of the robot are randomly selected in the cube space with an edge length of 700 mm on the front side of the Staubli TX60 robot. The measured poses are uniformly distributed in the cube space. The poses are measured by the laser tracker. The kinematic parameter errors identified are shown in Table 3. The average axial position error vector of the Staubli TX60 robot before calibration is 0.119 mm, 0.106 mm, and 0.405 mm, and the maximum axial position error vector is 0.362 mm, 0.449 mm, and 0.867 mm. The average axial position error vector of the Staubli TX60 robot after calibration is 0.022 mm, 0.020 mm, and 0.036 mm, and the maximum axial position error vector is 0.076 mm, 0.054 mm, and 0.102 mm. The position error distribution of the measured poses is shown in Figure 3. In this paper, the average comprehensive position accuracy Ep and the average comprehensive attitude accuracy Ea can be obtained using the following equation:where ΔPx, ΔPy, and ΔPz are the average axial position error and Δφα, Δφβ, and Δφγ are the average axial attitude error.

Compared with the uncalibrated robots, the average comprehensive position accuracy of the Staubli TX60 robot has been increased by 88.7%. The average axial attitude error vector of the Staubli TX60 robot calibration is 0.128°, 0.010°, and 0.050°, and the maximum axial attitude error vector is 0.248°, 0.237°, and 0.156°. The average axial attitude error vector of the Staubli TX60 robot after calibration is 0.061°, 0.028°, and 0.026°, and the maximum axial attitude error vector is 0.143°, 0.126°, and 0.085°. The attitude error distribution of the measured poses is shown in Figure 4. The average comprehensive attitude accuracy of the Staubli TX60 robot has been increased by 56.6%.

To verify the calibration performance, thirty different points are selected to recalculate the position and the attitude errors. The results are shown in Figures 3 and 4. The average comprehensive position accuracy of the Staubli TX60 robot has been increased by 55.2%, and the average comprehensive attitude accuracy of the Staubli TX60 robot has been increased by 30.2%. From the experimental results, it can be seen that the accuracy of the identified robot kinematic model has been significantly improved.

3. Pose Error Compensation

Pseudotarget iteration-based error compensation method with three different forms and the Newton–Raphson-based error compensation method are the typical error compensation methods. In this section, the principle and effectiveness of the four methods are compared through experiments.

3.1. Pseudotarget Iteration Method

The nominal kinematic parameter of the industrial robot is defined as c0. When the joint angle vector of the robot is q, the nominal pose of the robot is TN. The errors of the kinematic parameters are defined as Δc. Therefore, the actual kinematic parameter of the robot is c1 = c0+ Δc. In the compensation process, the kinematic parameter c1 is replaced with the parameter obtained by the robot calibration. The actual pose of the robot is TR. Therefore, the forward kinematics and the inverse kinematics of the robot are expressed as follows:

The expected pose of the robot is defined as Td. The aim of the pseudotarget iteration method is to find a pose Ts to obtain the joint angle qd with the nominal kinematic parameters. Therefore, the pseudotarget iteration method uses the inverse kinematics solution of the robot controller. The expression of the pseudotarget iteration method is shown as follows:where Ts is an offset pose with nominal parameters and qd is the approximate inverse kinematic solution f−1(c1, Td) of the calibration model.

The Taylor series expansion of equation (9) is carried out, and the higher-order terms are ignored. Then, the second term is expanded at the joint angle q0, which is the inverse solution of the expected pose Td in the nominal model. Then, the following equation can be obtained.

The pose error between T1 and Td is given as follows:where T1 is the first pose that the robot reaches with the joint angle q0.

The value of the third term on the right side of equation (9) can be ignored. Substituting equation (11) into equation (10), the following equation can be obtained:

Taking as the target pose, the joint angles q1 of the nominal inverse kinematics are recalculated. Based on the above process, the following equation is obtained:where T2 is the second pose that the robot reaches with the joint angles q1.

The offset pose Ts can be obtained by continuously superimposing the target error on the basis of the expected pose. When is met the accuracy requirements, the iteration is stopped. The iterative calculation equation is shown as follows:

It can be seen that the offset pose Ts of each iteration needs to compensate for the difference between the actual model pose and the expected pose. Equations (11) and (12) can be written in a matrix form based on the coordinate system transformation as follows:

Therefore, the matrix iteration equation of this method can be written as follows:

The poses of ten points (Pi) are selected and measured for error compensation verification. Firstly, the kinematic error compensation is implemented based on equations (13) and (15). The number of the iterative calculation is set as 5. The comprehensive position errors of each iterative calculation are shown in Figure 5. When the number of iterative calculations is 2, the comprehensive position error is close to 0.00 mm. The comprehensive position error after one iteration is less than 0.002 mm, which can satisfy the accuracy requirements.

Veitschegger et al. proposed an improved error compensation method [31]. The calculation process of the method is shown as the following equation. The principle of this method is consistent with the pseudotarget iteration method. The difference between the methods is that the error Δθ is not involved in the calculation of the pseudotarget pose. The error Δθ is substituted when the inverse solution of the pseudotarget pose is calculated. This method does not require iterative operations.where ∆θ is the identified error of the kinematic parameter θ and c2 is the identified kinematic parameter of the industrial robot without ∆θ error.

3.2. Newton–Raphson-Based Compensation Method

Gao et al. proposed another error compensation method based on Newton–Raphson. The method can be used to compensate kinematic parameter errors. The Newton–Raphson-based method uses the nominal kinematic model to solve the inverse kinematics as follows:

The pose Tc is calculated when the joint angle q1 is substituted into the actual kinematic model without Δθ as follows:

As defined above, the expected pose is Td. The Newton–Raphson-based compensation method is to find qs to satisfy the following equation:

The Taylor series expansion of equation (20) is carried out, and the higher-order terms are ignored. The expression is as follows:

Equation (21) is rewritten as follows:

The angle difference δq between q1 and qs can be obtained using the least square optimization algorithm to solve equation (22). The obtained angle difference δq is equivalent to converting other parameter errors into joint angle errors. The desired joint angles are calculated by the following equation:

Ten measured poses in the calibration pose set are randomly selected. Based on the numerical simulation, the average comprehensive position error after one iteration of the least square algorithm is less than 0.001 mm. Therefore, the optimization calculation of this method needs only one iteration.

3.3. Performance Comparison of the Error Compensation Methods

Twenty points were randomly selected to compare the effectiveness of the above error compensation methods. The average comprehensive position error of the robot is 0.052 mm after calibration, and the average comprehensive attitude error is 0.070°. When the pseudotarget iteration method based on differential form (method 1) is applied, the average comprehensive position error and the average comprehensive attitude error of the robot after error compensation are 0.0539 mm and 0.071°, respectively. When the pseudotarget iteration method based on matrix form (method 2) is applied, the average comprehensive position error and the average comprehensive attitude error of the robot after error compensation are 0.0533 mm and 0.070°, respectively. When the improved differential form method (method 3) is applied, the average comprehensive position error and the average comprehensive attitude error of the robot after error compensation are 0.0584 mm and 0.072°, respectively. When the Newton–Raphson error compensation method (method 4) is applied, the average comprehensive position error and the average comprehensive attitude error of the robot after error compensation are 0.0533 mm and 0.071°, respectively. It can be concluded that the effectiveness of the four error compensation methods is the same. The axial errors obtained by different error compensation methods are, respectively, shown in Figures 6 and 7. The maximum axial position error of the robot is less than 0.07 mm, and the maximum axial attitude error of the robot is less than 0.1°. The position error in Z-axis and the attitude error in X-axis after error compensation are larger than those in the other two axes.

The comparison of the position error and attitude error of the four compensation methods is shown in Table 4. The average error, maximum error, and standard deviation in the three axes are compared. It can be seen from the table that method 1 and method 2 show better effects than method 3 and method 4. The compensation accuracy of method 3 is the worst.

Except for the contrast in accuracy, the following two aspects are summarized:(1)In the first three error compensation methods, the inverse kinematics solution of the nominal model should be solved twice. In method 4, the inverse kinematics solution number of the nominal model is only 1. However, method 2 and method 4 need to calculate the inverse of the matrix. The real-time performances of these two methods are lower. Therefore, the calculation efficiency of methods 1 and 3 is higher.(2)In the four methods, the inverse kinematics solution of the robot is needed to be solved. Due to the errors of the kinematic parameters, there is a certain difference between the nominal motion space and the actual motion space, which is shown in Figure 8. The error compensation method should be applied when the workspace is in the overlap area between the nominal motion space and the actual motion space.

To sum up, method 1 is better than the other three methods.

4. Conclusion

This paper discusses the effectiveness of kinematic error compensation methods for serial robots through experiments. Firstly, the pose error model of the serial robot is established based on the M-DH model. The kinematic errors are identified based on the robot calibration platform. The results show that the accuracy of the Staubli TX60 robot has been greatly improved. The average comprehensive position accuracy is increased by 88.7%, and the average comprehensive attitude accuracy is increased by 56.6%. Secondly, the principles of pseudotarget iteration-based error compensation method with three different forms and Newton–Raphson-based error compensation method are presented and analyzed. The pseudotarget iteration-based error compensation method includes three different forms. The effectiveness of each error compensation method is compared through experiments. The experimental results show that all of the four error compensation methods can achieve error compensation well. Considering both the accuracy and the calculation efficiency, method 1 is superior to the other three methods, and method 3 is the worst. In addition, the four error compensation methods should be applied when the workspace is in the overlap area between the nominal motion space and the actual motion space.

Data Availability

The raw data required to reproduce these findings cannot be shared at this time as the data also form part of an ongoing study.

Conflicts of Interest

The authors declare that there are no conflicts of interest regarding the publication of this article.

Acknowledgments

This work was supported in part by the Natural Science Foundation of China under grant no. 51905258, the Jiangsu Province Universities Natural Science Research Program (17KJD460006), the China Postdoctoral Science Foundation (2019M650095), and Scientific Research Funds of the Nanjing Institute of Technology (YKJ201717).