Keywords

1 Introduction

The robot manipulators are widely used in the industry. Although the robots are high repeatability, they are well-known by their low accuracy [1, 2]. The errors of the robot end-effector mostly come from geometric errors and non-geometric errors. The geometric errors are the results of misalignments, incorrect in manufacturing, and assembly robot. The non-geometric errors may come from many non-geometric sources, such as joint and link compliance, temperature variation, gear transmission, etc. Among the non-geometric errors, the compliance errors are dominant. These errors are caused by the flexibility of joints and links under the link self-gravity and external payload.

Geometric calibration methods are widely examined and become mature. The most famous kinematic calibration method, the D-H model is suggested by Denavit-Hartenberg [3,4,5]. This method is widely used in kinematic calibration by many researchers recently [6,7,8]. Moreover, the other geometric calibration methods are CPC model [9, 10], POE model [11, 12] and the zero-reference position method [13, 14]. However, these calibration methods do not consider the non-geometric errors. On the other hand, some studies used another approach to investigate joint compliance errors [15, 16]. However, these methods neglected effect of the geometric errors.

Some works have been proposed to deal with kinematic and compliance calibration. For instance, a calibration method to calibrate the geometric errors and compensate the joint by radial basis function (RBF) [17] is proposed by Jang et al. However, the work [17] focused on calibrating the geometric parameters and compensating the compliance errors by compensating the joint (“joint level” calibration [1]). The work also needs to divide the robot working space into many subspaces and required many measurements and consuming a lot of time. Meggiolaro et al. proposed a method to approximate the compliance errors by a polynomial function of joint parameters and wrench using torque sensors [18]. Zhou and Hee-Jung proposed a method to simultaneously calibrate the geometric and joint stiffness parameters of the robot [19]. However, this method linearized the relationship between effective torques and joint compliance errors. Recently, some studies have been performed on joint stiffness calibration [20,21,22] with the need of the torques sensors.

This study proposed a new calibration algorithm for robotic manipulators. The method includes the kinematic calibration and non-geometric compensation with a RBF compensator that compensates for compliance errors based on the effective torques. It is assumed that the gravity compensation torques are nonlinearity related to the compliance errors. These relationships can be constructed by a RBF. The advantages of the suggested method are easy for implementing, removing the need for torque sensors, high ability to enhance the precision of the manipulator. These advantages are firmly confirmed by the experimental studies in contrasting with 2 other methods such as the conventional kinematic calibration and the method for simultaneously calibrate the geometric and joint stiffness parameters of the robot.

Following the introduction. Section 2 presents the kinematic model of the YS 100 robot. In Sect. 3, the geometrical and the gravity compensator using a Radial basis function that is based on the effective torques are presented. Sections 4 is devoted to the experimental calibration result of the proposed method in contrasting with other methods. Section 5 summarizes the abilities and advantages of the proposed method.

2 Kinematic Model of the YS100 Robot

YS100 is a 6 DOF serial robot [19]. The kinematic structure of it is briefly described in Fig. 1 and Table 1.

Fig. 1.
figure 1

Kinematic structure of the YS 100 robot.

Table 1. Nominal D-H parameters of the Hyundai robot YS100.

The transformation that relates base frame {0} to tool frame{T}:

$$ {}_{{{\text{E}}\,}}^{0\,} \varvec{T} = {}_{1\,}^{0} \varvec{T}\text{(}\theta_{{\,\text{1}}} \text{)}{}_{2\,}^{1\,} \varvec{T}\text{(}\theta_{\text{2}} \text{)}{}_{3}^{2} \varvec{T}\text{(}\theta_{\text{3}} \text{)}{}_{4\,}^{3} \varvec{T}\text{(}\theta_{\text{4}} \text{)}{}_{5\,}^{4} \varvec{T}\text{(}\theta_{\text{5}} \text{)}{}_{6\,}^{5} \varvec{T}\text{(}\theta_{\text{6}} \text{)}{}_{{{\text{E}}\,}}^{6\,} \varvec{T} $$
(1)

The end-effector transformation:

$$ (_{T}^{6} )T = Tr_{X} (a_{6} )Tr_{Y} (b_{6} )Tr_{Z} (d_{T} ) $$
(2)

3 Identification Kinematic Parameters and Compliance Compensation Based on the Effective Torques Using a Radial Basis Function

Assuming that the robot’s end-effector position Preal is calculated by the following equation:

$$ P_{real} = P_{kin} + \Delta P_{kin} + \Delta P_{c} + \Delta P_{extra} $$
(3)

where \( P_{kin} \) is the position of the end effector calculated by the kinematic parameter,\( \Delta P_{kin} \) is the position error caused by the geometric error, \( \Delta P_{c} \) is the position error due to the joint compliance, and \( \Delta P_{extra} \) is the positional residual error that is not modeled. Assuming that geometric errors and joint deflection errors are the main parts in causing the position errors \( P_{real} \) (\( \Delta P_{extra} = 0 \)). The error model can be expressed as:

$$ \Delta P = \Delta P_{kin} + \Delta P_{c} = P_{real} - P_{kin} $$
(4)

The position errors caused by geometric errors \( \Delta P_{kin} \) in the Eq. 4 could be identified by the conventional kinematic calibration [3,4,5]. \( \Delta P_{kin} \) can be expressed as

$$ \Delta P_{kin} = J_{kin} \Delta \phi $$
(5)

where \( J_{kin} \)(\( 3 \times n \)) is a kinematic Jacobian matrix [1, 19]. \( \Delta \phi \) is a \( n \times 1 \) kinematic parameter error vector. \( n \) is the number of the calibrated kinematic parameters. The total number of kinematic parameters is equal to 32. However, the 6 DOF revolute robot has several dependencies between some parameters. These dependency parameters are {\( \Delta \theta_{1} ,\Delta \theta_{0} \)}, {\( \Delta d_{1} ,\Delta d_{0} \)}, {\( \Delta d_{3} ,\Delta d_{2} \)}, {\( \Delta z_{T} ,\Delta d_{6} \)}, {\( (\Delta x_{T} ,\Delta y_{T} ),\Delta \theta_{6} \)}. In each pair, the parameter errors cannot be identified together. Therefore, the dependency parameters that are chosen to calibrate are {\( \Delta \theta_{1} \), \( \Delta d_{1} \), \( \Delta d_{3} \), \( \Delta x_{T} \), \( \Delta y_{T} \), \( \Delta z_{T} \)} while the other error parameter in each pair is set to the nominal parameter value. So, the number of calibrated kinematic is reduced to 27.

The Eq. 5 can be solved by the least-square method to overcome the effect of noise and uncertainty:

$$ \Delta \phi = [ ( {\text{J}}^{\text{T}} {\text{J)}}^{ - 1} {\text{J}}^{\text{T}} ]\Delta P $$
(6)

The positional error \( \Delta P \) is calculated by

$$ \Delta P = P_{m} - P_{kin} $$
(7)

where Pm is the measured position vector and Pkin is the computed position vector by the recent kinematic parameters. The Eq. (6) is employed repetitive until the geometric parameters converge. Through the kinematic calibration process, the \( P_{kin} \) converges to the \( P_{{_{kin} }}^{c} \) value. The position errors of the robot end-effector after kinematic calibration process are calculated by:

$$ \Delta P_{res} = P_{m} - P_{kin}^{c} $$
(8)

Assuming that the position errors due to joint deflection errors are the main parts in causing these residual position errors (\( \Delta P_{res} = \Delta P_{c} \)). The joint deflections under link self-gravity and external payload are also assumed to be dominant in causing compliance errors. Therefore, the joint deflection errors can be calculated from the related effective torque of joints.

It should be noted that previous literatures [15, 19] constructed the compliance errors by linearizing the relationship of the effective torques and the joint compliances. However, there are some residual errors that could not be neglected caused by the nonlinear relation between joint torques and joint deflections. For further enhanced the robot precision, the relationship of the effective torque and the residual errors is constructed by a RBF in this paper. The RBF has 6 inputs that represent the total effective torque in 6 robot joints, 40 nodes in the hidden layer, and 3 nodes in the output layer that represent three elements of the position error vector.

The total effective torques in the robot jth joint under related gravity forces are given as:

$$ \tau_{i} = \sum\limits_{j = i}^{N + 1} {\tau_{i,j} } = \sum\limits_{j = i}^{N + 1} {J_{{\theta_{{_{i,j} }} }}^{T} } F_{j} $$
(9)

where N = 6 is the number of DOF of the robot and FN+1 is the gravity force due to payload Here, the gravity force accompanying to jth link is calculated by

$$ F_{j} \, = \,\left[ {\begin{array}{*{20}l} 0 \hfill & 0 \hfill & { - M_{j} g} \hfill \\ \end{array} } \right] $$
(10)

where \( M_{j} \) is the mass of the jth link and g is the gravity coefficient. The transpose of the Jacobian matrix is used as a force transformation to find the effective joint torques τi,j in the ith joint due to the gravity force in the jth link. The Jacobian matrix is defined as

$$ J_{{\theta_{{_{i,j} }} }} \, = \,z_{i} \times l_{i,j} $$
(11)

where \( l_{i,j} \) is the 3 × 1 vector between the origin of the ith frame and the mass center of the jth link.

The total effective torques are set to be the input of the RBF. Figure 2 shows the structure of the RBF. The output of the hidden node i in the RBF layer is calculated as follow:

$$ o_{j} = e^{{ - n^{2} }} $$
(12)
Fig. 2.
figure 2

Structure of the RBF.

where n is a transfer function that describes the vector distance between the weight vector wi and the input vector p, multiplied by the bias bi.

$$ n = \left\| {{\text{w}}_{i} - p} \right\|b_{i} $$
(13)

The output layer is a linear function with 3 nodes in the output layer that represent three elements of the position error vector.

The output of the RBF is used to compensate for the compliance error(which is assumed to be the residual error \( \Delta P_{res} = \Delta P_{c} \)). Therefore, the residual error after compensated by the RBF is calculated by:

$$ e = \Delta P_{res} - P_{nn} $$
(14)

In this work, the weights and bias of the RBF are trained by the MATLAB toolbox that creates a two-layer network. The hidden layer is the RBF layer (Eq. 12, 13). The output layer is a linear layer. At the beginning, there are no neurons in the hidden layer. The learning process is carried out following the steps below:

  • Run the network and find the input vector with the greatest error.

  • A RBF neuron is added with weights equal to that vector.

  • The linear layer weights are redesigned to minimize error.

  • Repeat until convergence.

In order to keep the RBF layer from increasing too much, the number of nodes in this layer are limited at 40 nodes. Overall, the suggested method could be described in the following flowchart (Fig. 3).

Fig. 3.
figure 3

Flowchart of the proposed method.

4 Experiment and Results

The experimental system is shown in Fig. 4. The 6 DOF robot manipulator (YS100). In this work, the mass of link jth Mj (Eq. 10) is provided by the robot’s manufacturer. The external payload weight is 110 kg. Therefore, the weight matrix is descried as follow:

$$ M\, = \,\left[ {\begin{array}{*{20}l} { 1 9 6. 7} \hfill & { 7 9. 2 5} \hfill & { 1 7 0. 2 7} \hfill & { 1 0. 5 8} \hfill & { 2 2. 3 3} \hfill & { 2. 0} \hfill & { 1 1 0} \hfill \\ \end{array} } \right] $$
(15)
Fig. 4.
figure 4

Experimental setup.

An API laser tracker (accuracy of 0.01 mm/m, repeatability of ±0.006 mm/m) and an accompanying laser reflector are used to perform the calibration process. The proposed method (RBF-TCM) is used to calibrate the YS100 robot to show the advantage of the method in comparing with 2 others methods including the kinematic calibration method (KM) [3,4,5], the simultaneous identification of joint compliance and kinematic parameters methods (SKCM) [19] in the experimental study.

4.1 Experimental Calibration

The robot configuration data are randomly collected in the working space and classified into 2 sets. Set Q1 including 50 robot configurations is employed in the calibration process and the other set of 50 robot configurations (Q2) is used in the validation process. By using the conventional calibration method (Eq. 6), 27 geometric parameters are identified. The results are demonstrated in Table 2. The residual errors and the computed torques are used for training the RBF to determine the weights and bias of the RBF. It should be noted here the reason why the RBF is used in this working rather than the conventional fed forward neural network. In the conventional feedforward neural network, the sigmoid neurons can have outputs over a large region of the input space, while radial basis neurons only respond to relatively small regions of the input space [23]. Therefore, the RBF could be said to be more stable in responding to noises and uncertainties inputs. However, the drawback of this method is that the larger the input space the more radial basis neurons are required [24]. The experimental calibration processes are carried out by 3 different calibration methods such as conventional kinematic calibration, SKCM, and RBF-TCM. The results of these calibration methods are shown in Fig. 5 and Table 3.

Table 2. D-H parameters of the Hyundai robot YS100.
Fig. 5.
figure 5

Residual errors of the YS100 robot after calibration.

Table 3. The absolute position accuracy of the YS100 robot (Calibration).

The calibration results show that the precision of the robot after calibrated by the proposed method is dramatically reduced. By employing the RBF-TCM method, the position errors are lower than the results by other methods. In comparing to the conventional kinematic calibration method, the proposed method reduces the mean of position errors from 0.6894 mm to 0.2785 mm (precise increasing by 59.6%). It also increases the accuracy by 54.08% in comparison to the results generated by the SKCM method (from 0. 6065 mm to 0.2785 mm). The suggested algorithm also generates the lowest maximum position error (0.9332 mm), and the lowest standard deviation (0.2095 mm).

4.2 Experimental Validation Results

The proposed method should be validated by another robot configuration to demonstrate the ability of it over the working space. The robot configuration set Q2 that is totally different from Q1 is hired for the validation process with 3 different methods.

By employing the method, the position errors are lower than the results by other methods in the validation process (Table 4 and Fig. 6). In comparing to the conventional kinematic calibration method, the proposed method reduces the mean of position errors from 0.7245 mm to 0.2802 mm (precise increasing by 61.33%). It also increases the accuracy by 56.21% in comparison to the results generated by the SKCM method (0.6398 mm to 0.2802 mm). The suggested algorithm also generates the lowest maximum position error (0.7846 mm), and the lowest standard deviation (0.2084 mm).

Table 4. The absolute position accuracy of the YS100 robot (Validation).
Fig. 6.
figure 6

Residual errors of the YS100 robot after validation.

4.3 Discussion and Future Studying

In previous literatures [15, 19], the relationship of joint deflections of robot and the effective torques are linearized:

$$ \Delta \theta_{c} \, = \,\tau C $$
(16)

where \( \Delta \theta_{c} \) is the \( N \times 1 \) joint deflection vector, \( \tau \) is the diagonal effective torque matrix, C is the \( N \times 1 \) joint compliance vector. Then, the Cartesian position errors due to the joint compliances can be modeled as:

$$ \Delta P_{c} \, = \,J_{e} \Delta \theta_{c} \, = \,J_{e} \tau C $$
(17)

where \( J_{e} \) is vector of joint compliance parameters that is computed by the following published work [25]. \( J_{e} \tau \) is the transformation matrix relating the joint compliance parameters and the deflections of robot end-effector. It should be noted here that the effective torques in the ith joint is not only due to the gravity force related to the ith link but also due to the gravity forces related to both the link after and the external load. In this work, the relationship of the effective torque \( \tau \) and the positional errors due to the compliance errors \( \Delta P_{c} \) could be constructed by a RBF for higher increasing the precision of the robot.

The work will be expanded in the future by implementing the optimizing method to select the calibration poses for better calibration results.

5 Conclusion

In this work, a new robotic calibration method is proposed for reducing the positional errors of the robot manipulator. First, geometric errors of a robot are identified by using a conventional kinematic calibration model of the robot. Then, a radial basis function is constructed for compensating the compliance errors based on the effective torques for further increasing the positional precision of the robot. By using a RBF, the relationship of the effective torque and the compliance errors is constructed for higher increasing the precision of the robot. The advantages of the suggested method are easy for implementing, removing the need for torque sensors, high ability to enhance the precision of the manipulator. These advantages are firmly confirmed by the experimental studies on a YS100 robot in contrasting with 2 other methods such as the conventional kinematic calibration and the method for simultaneously calibrate the geometric and joint stiffness parameters of the robot.