Abstract

The positioning accuracy of a robot is of great significance in advanced robotic manufacturing systems. This paper proposes a novel calibration method for improving robot positioning accuracy. First of all, geometric parameters are identified on the basis of the product of exponentials (POE) formula. The errors of the reduction ratio and the coupling ratio are identified at the same time. Then, joint stiffness identification is carried out by adding a load to the end-effector. Finally, residual errors caused by nongeometric parameters are compensated by a multilayer perceptron neural network (MLPNN) based on beetle swarm optimization algorithm. The calibration is implemented on a SIASUN SR210D robot manipulator. Results show that the proposed method possesses better performance in terms of faster convergence and higher precision.

1. Introduction

The positioning accuracy of robots is of great significance in advanced robotic manufacturing systems. In general, the robot shows good repeatability, but poor positioning accuracy. Many factors would result in errors in positioning, including set-up errors, manufacturing tolerance, wear and tear, transmission errors, and compliance [1]. Therefore, researchers have focused on how to improve the positioning accuracy of a robot by errors compensation according to the factors mentioned above.

The calibration technique can improve the robot’s positioning accuracy through software algorithm without changing its mechanical structure or design. Generally, calibration can be classified into two types, namely geometric and nongeometric calibration. Almost 80% of robot positioning errors are caused by errors of geometric parameters, including link length errors, link twist angle errors, link offset, and joint angle offsets [2]. Therefore, most researches have concentrated on kinematic-based calibration [39]. Most of the researchers employed the D-H model which employs a minimum set of parameters to describe the relationship of joint coordinates for calibration. However, D-H model is not continuous when two consecutive joint axes are parallel or nearly parallel. In order to overcome these drawbacks, Hayati proposed a new model namely MDH model by adding a redundant parameter to the D-H model [10]. However, both the two methods are complicated in the process of modeling a manipulator. Brockett firstly used the POE formula to describe an open-chain robot [11]. The POE formula possesses a simpler expression to describe the relationship between the joint angles and the end-effector’s position and posture. Additionally, previous studies mostly focused on the calibration of the link lengths and the joint offsets, and little attention has been paid to the errors of the reduction ratio and the coupling ratio. The reduction ratio and coupling ratio errors mainly caused by the deviation during manufacturing and assembly process will lead to joint angle errors, further resulting in a decline in the positioning accuracy. Moreover, owing to the nonlinear trigonometric relationship between joint angles and the pose of endpoint, it is complicated to identify the transmission errors using the DH model [12]. The POE formula, however, possesses a simpler expression.

However, the kinematic-based calibration has the following limitations: (1) the model only takes the geometric factors into account, but the nongeometric factors such as backlash and joint compliance, which may have significant influence on positioning accuracy, are ignored. (2) The identification process is a complex numerical procedure which may suffer from the numerical problem of ill-conditioning. (3) The implementation of the identified model is problematic due to the difficulty of modifying the controller parameters [13].

In fact, the nongeometric errors are an important component of the parameters identification, especially in high-precision application scenarios. The positioning errors caused by joint stiffness account for 6%∼8% as well as other nongeometric errors such as gear backlash and temperature drift [14]. Some researchers investigated both the kinematic parameters and joint compliance [15, 16]. However, other nongeometric errors still affect the positioning accuracy significantly. Especially for a heavy load robot, not only the joint compliance but also the link compliance affects the accuracy [17, 18].

Recently, for nonparametric calibration, some intelligent algorithms, such as genetic algorithm [7, 19, 20], maximum likelihood estimation [21, 22], neural network [2329], and various hybrid algorithms [30], have emerged. Among them, neural network has been widely employed to build the relationship, especially nonlinear relationship between inputs and outputs. It can approximate any nonlinear function with arbitrary precision [31]. The neural network is utilized to build the relationship between the end-effector position and the error of the position in [25]. However, the positioning error depends on the configurations. In [26], a multilayer perceptron neural network is utilized to describe the relationship between the joint angles and the corresponding joint errors. Nguyen proposed a technique for the calibration of industrial robots by combining the geometric model-based calibration method and the ANN to identify the kinematic errors, joint compliance errors, and the nongeometric errors [29]. But, at the same time, the BP neural network has the problem that the performance relies too much on the input data and initial values of weights and biases and easily falls into the local optimum. To overcome these drawbacks, researchers have proposed many hybrid algorithms such as GA-BPNN [32, 33] and PSO-BPNN [34]. But, convergence rate of these algorithms is relatively slow, and implementation of code is complex.

In this paper, an enhanced POE-based method is proposed for the identification of geometric parameters, reduction ratio, and coupling ratio. Joint stiffness identification is carried out by adding a load to the end-effector. For the nongeometric errors compensation, an optimized MLPNN based on a hybrid optimization method of beetle antennae search algorithm and particle swarm optimization is proposed. Experiments are carried out on a SIASUN SR210D robot manipulator to validate the proposed method by using a laser tracker to measure the position of the Spherical Mounted Retroreflector (SMR) located at the end flange of the manipulator.

The rest of the paper is organized as follows. In Section 2, the kinematic model of the SIASUN SR210D robot manipulator is presented. In Section 3, the POE-based error model including the transmission errors is established. Section 4 proposes the joint stiffness identification method. In Section 5, a hybrid beetle swarm optimization and MLPNN algorithm are presented for the nongeometric errors compensation. In Section 6, Compensation verification and analysis are presented. In Section 7, conclusions and future works are presented.

2. Kinematic Model of the SIASUN SR210D Robot Manipulator

In this section, a kinematic model of the SIASUN SR210D robot manipulator is described in detail. The structure of the 6R manipulator is in Figure 1. are the link lengths and are the joint angular velocities, respectively. The nominal value of robot structure parameters mentioned above is listed in Table 1.

Then, the screw of each joint is

The forward kinematics can be expressed as mentioned below:where is the angle of the joint and is the end-effector position in the base frame corresponding to .

3. Geometric Parameters and Transmission Errors Identification

3.1. Model of Geometric Parameters Errors

The position of the tool center point (TCP) in the measure frame is shown below:where is the position of the TCP, is a homogenous matrix that represents the transformation from the measuring device frame to the base frame, and represents the position of TCP expressed in the base frame corresponding to , .

Then, we have the deviation of the TCP position by taking the differential on both sides of equation (3):where

Taking a close observation of (4), we notice that dM × M−1 ∈ se(3),  × −1 ∈ se(3), and the element s belonging to lie algebra satisfies

can be expressed as

Since rigid body motion can be realized by a rotation and a translation about an axis, M can be expressed as

Take the differential on both sides:

The matrix is

Take the differential on both sides:where is

3.2. Model of Transmission Errors

Transmission errors mainly include the reduction ratio error and coupling ratio error. The errors are caused by the process of manufacturing and assembly. Both the errors lead to positioning inaccuracy.

Considering the transmission errors, the nominal value of the joint angle can be given bywhere and are the nominal and identified reduction ratios of the joint. and are the nominal and identified coupling ratios. and are the nominal and actual output angles of the joint reducer. is the joint motor rotation angle. ki and hji are the errors of the reduction ratio and the coupling ratio, namely the transmission errors.

Then, the joint angle θi can be expressed aswhere θi0 is the zero positioning error of the joint angle θi, namely the joint offset and θj is the joint angle which is coupled with θi.

Furthermore, the deviation of the joint angle θi can be deduced as

3.3. Linearization of the Error Model

Linearization of the error model is a premise for parameters identification. The error model can be obtained by combining the two error models mentioned above aswherewhere can be expressed as a homogeneous matrix through Taylor expansion and the adjoint transformation associated with can be expressed as a 6 × 6 matrix. Equation (16) can be deduced aswherewhere is the actual TCP position measured by the laser tracker and is the nominal TCP position obtained by the forward kinematics. The parameters to be identified can be expressed as

A is the corresponding coefficient matrix which can be expressed as

With the measurement of the TCP position at different configurations, we can get the following equation set:where n is the number of measurements.

The least-squares solution for is

4. Joint Stiffness Identification

The stiffness of the manipulator arm is much greater than that of the joint. For this reason, the joint stiffness identification is investigated in this section.

For a joint, the dynamic model can be described aswhere is the inertial matrix, is the Coriolis and centrifugal terms, relates to the gravitational torque, and is the friction torque in the joint. is the input torque from the joint motor.

On the assumption that the angular deformation of the reducer is proportional to the input torque, the relationship between the input torque and the deformation of the reducer is as follows.where is the stiffness coefficient of the joint and is the angular deformation of the joint. The joint torque is obtained aswhere is the motor current that can be read directly from the controller of the robot. is the motor potential constant, and is the magnetic flux.

For a manipulator, the stiffness matrix of the robot joint can be obtained as follows by ignoring the interaction of each joint.where n is the number of degrees of freedom.

Substitute equation (25) into equation (24), and the relationship between joint angle deformation and motor control current can be given by

The flexibility matrix of the robot joint is as follows:

According to the differential error relationship, the joint angle deviation vector can be obtained.

Since only the gravity load is loaded during the experiment, the direction of gravity is consistent with the direction of the first axis of the robot and the moment of gravity decomposition to the first axis is 0, and the first axis is not identified. Similarly, the flexibility coefficient of the sixth axis is not identified.

Substitute the flexibility matrix into the equation below to improve the positioning accuracy by compensating the joint angles.where is the modified joint angle value of the robot. is the nominal value of the joint angle, and the vector is the current value of each joint motor.

5. MLPNN Based on a Hybrid Optimization Method of Beetle Antennae Search Algorithm and Particle Swarm Optimization for Nongeometric Errors Compensation

The positioning error is still large after the geometric parameters, transmission errors, and joint stiffness compensation. The residual positioning errors are caused by nongeometric errors which is difficult to model. In order to overcome the drawbacks, in this section, a MLPNN based on a new hybrid optimization method is proposed. This new model will be presented in details.

5.1. Beetle Antennae Search Algorithm (BAS)

The beetle antennae search algorithm (BAS) is a metaheuristic algorithm that is inspired by the searching behavior of longhorn beetles [35, 36]. A vector at tth time instant (t = 1, 2, …) denotes the position of the beetle. At position x, is defined as the fitness function to represent the concentration of odour. Normally, we can use two rules to simplify the algorithm, including search and detection behavior. In an unknown environment, the beetle searches randomly. A normalized random unit vector is utilized to model the searching behavior as follows:where rands(.) represents a random function and m is the number of dimensions of the position. and are defined to imitate the searching behavior of both the right and left antennae:where d is the sensing length of antennae.

An iterative form is proposed to model the detecting behavior:where is the step size and sign(.) represents a sign function.

The antennae length and step size are updated according to the following formula.

Compared with other heuristic algorithms such as PSO, GA, and ABC, the BAS algorithm possesses better performance in terms of faster speed and simpler implementation. A second order Michalewicz function shown below was used to validate the algorithm.where the minimized value satisfies  = −1.8013, locating in  = (2.20, 1.57). The initial values of and are 2 and 0.5. Taking the absolute error less than 0.0001 as the end evolution, the time these algorithms mentioned above takes is shown in Table 2.

The results showed that the search speed of BAS algorithm was tremendous. The BAS algorithm can fit well for the real-time task.

5.2. Beetle Swarm Optimization (BSO)

The performance of beetle antennae search algorithm relies heavily on the initial position, and it will easily fall into the local optimum when dealing with high-dimensional problems [3739]. In order to overcome these drawbacks, further improvements are made by combining the antennae search algorithm and particle swarm optimization. That is the beetle swarm optimization algorithm.

In beetle swarm optimization, each particle in the standard PSO is defined as a beetle. Each beetle represents a potential solution to the optimization problem. In the iterative process, the update of the position relies not only on the individual and global historical best solution but also on the way of beetle antennae search. The formula can be expressed as follows [34]:where is the beetle, is the dimension, is the current number of iterations, is the speed of the beetle, is the increase in movement, and is a positive constant. is expressed as:where is the inertia weight, and are constants, and and are two random functions in (0, 1). and are the individual and group extremities.

The inertia weight is decreasing in the process as follows:where and represent the maximum and minimum values of and and are the current number of iterations and the maximum number of iterations.

defines the increase in movement and is expressed aswhere is the step size. The position of the left and right antenna can be expressed as

5.3. MLPNN

Artificial neural network and, in particular, the multilayer perceptron neural networks are widely used in many application areas over the years. Typically, the multilayer perceptron neural network contains three kinds of layers, which are the input layer, hidden layer, and output layer. It is claimed that a three-layered feed-forward neural network can approximate any nonlinear function with arbitrary accuracy. The number of neurons in input and output layers is normally selected according to the actual needs. However, the best number of neurons in the hidden layer can just be determined by trial-and-error methods.

Generally, each neuron can be denoted by the following equation:where and are the input and output values of the jth neuron, respectively; denotes the connection weight from the ith neuron in the previous layer to the jth neuron in the latter layer; represents bias value in the jth neuron; and is normally a sigmoid function as follows:

Its derivation is

The error of the neuron in the output layer iswhere and are the desired and actual value of the neuron in the output layer. The total error of the output layer iswhere m is the number of neurons in the output layer.

For nongeometric errors compensation, the joint angles are selected as the inputs and the positioning errors in each axis are selected as the outputs. By using the Jacobian matrix, the positioning errors are mapped to the errors of joint angles. The compensation process is shown in Figure 2.

5.4. The MLPNN Optimized by BSO

The validity and accuracy of MLFNN may be reduced if the weights and biases are improperly selected. The BSO algorithm is used to optimize the network parameters of MLFNN in this process. In this section, the BSO-MLFNN method is proposed to overcome the shortcomings of low accuracy. The process is shown in Figure 3.

6. Compensation Verification and Analysis

As shown in Figure 4, a spherical mounted retroreflector (SMR) was mounted at the end flange of the manipulator, and the position of the SMR, namely, the tool center point (TCP) position, was measured by a laser tracker (FARO Vantage) with the positioning accuracy of 10 μm + 2.5 μm/m. Experiments were performed on a heavy load SIASUN SR210D robot.

The main steps of the experiment were as follows: (1) a set of 50 robot joint angle values in the controller and the corresponding positions without any load were obtained in the measuring coordinate system. Geometric parameters and transmission errors were identified using the improved POE model. (2) Identify the joint stiffness by measuring 50 points with a 210 kg load after geometric parameters and transmission errors compensation. (3) Compensate the nongeometric errors based on the proposed BSO-MLPNN by measuring 200 points after the two steps mentioned above.

The measurement points should be selected evenly in the workspace, so that the measuring configurations should go through all controllable DoFs and close to the boundary of the workspace, where the maximum errors are most prominent.

6.1. Geometric Parameters and Transmission Errors Identification

According to equation (22), the actual geometric parameters, transmission errors and coupling ratio can be identified. The nominal and identified value of geometric parameters and reduction ratio are shown in Tables 3 and 4.

The nominal coupling ratio error is 0 and the identified coupling ratio error is . The positioning accuracy of the 50 points before and after calibration is shown in Figure 5. The average positioning accuracy of measurement points is enhanced from 1.1288 mm to 0.2898 mm. For validation, another set of 50 points is selected. The validation results show that the average positioning accuracy is 0.3008 mm which is 0.011 mm larger than 0.2898 mm. Details are presented in Table 5.

6.2. Stiffness Identification and Compensation

According to equation (28), the joint stiffness is identified. The stiffness results are shown in Table 6. The positioning accuracy of the 50 points before and after calibration is shown in Figure 6. The average positioning accuracy is enhanced from 7.0261 mm to 0.9847 mm. Details are presented in Table 7.

6.3. Nongeometric Errors Compensation Based on BSO-MLPNN

Figure 6 shows that the positioning errors are still large after the geometric parameters, transmission errors, and the joint stiffness compensation. These errors caused by nongeometric sources are compensated by the BSO-MLPNN method. For this purpose, 200 evenly distributed points in the workspace and corresponding joint angles are collected for training the BSO-MLPNN. In the training process, joint angles are selected as the inputs and the residual positioning errors are selected as the outputs. The residual positioning errors in each axis are shown in Figure 7.

The positioning accuracy before and after nongeometric calibration at the measurement points is shown in Figure 8. The results show that, after the nongeometric errors compensation at the measurement points, the average positioning accuracy is enhanced from 0.9262 (mm) to 0.5907 (mm). Details are shown in Table 8.

Normally, the positioning accuracy of the measurement points is higher than that of the validation points. For validation, another set of 200 points are selected. The positioning errors are shown in Figure 9. The validation results show that the average positioning accuracy is enhanced from 0.9370 mm to 0.6522 mm. Details are shown in Table 9.

Therefore, the proposed three stages calibration method including geometric parameters, transmission errors, joint stiffness, and nongeometric errors compensation is effective.

7. Conclusion and Future Works

This paper proposed a three-stage calibration method for enhancing robot positioning accuracy. The geometric parameters and transmission errors are identified in the first stage. Then, joint stiffness compensation is carried out. For the nongeometric errors compensation, a hybrid algorithm, namely, BSO-MLPNN, is introduced.

Experiments were performed on the SIASUN SR210D robot manipulator. The average positioning accuracy was enhanced from 7.0261 mm to 0.5907 mm. Results demonstrated the effectiveness and correctness of the proposed method. In addition, the validation results showed that the manipulator after calibration has the same level of positioning accuracy in the entire workspace.

In future, nongeometric factors will be modeled in order to obtain more accurate knowledge of error sources and accelerate the convergence rate.

Data Availability

The authors declare that all relevant data within the paper are fully available without restriction.

Conflicts of Interest

The authors declare no conflicts of interest.

Acknowledgments

This research was supported by the 2017 National Key R&D Program of China (no. 2017YFB1301400).