Abstract

Joint offset calibration is one of the most important methods to improve the positioning accuracy for industrial robots. This paper presents an efficient method to calibrate industrial robot joint offset. The proposed method mainly relies on a laser pointer mounted on the robot end-effector and a position sensitive device (PSD) located in the work space arbitrarily. A vision based control was employed to aid the laser beam shooting at the center of PSD surface from several initial robot postures. For each shoot, the laser beam was a line in space which can be determined by the robot joint angles and their offsets which were recorded when the laser beam was brought to the center of the PSD surface. Therefore, there are several lines in space parameterized by robot joint offsets only and all these lines were constrained by the same point, that is, the center of the PSD surface. Consequently, an optimization model was formulated and the Levenberg-Marquardt (LM) algorithm was employed to identify the joint offsets. The developed calibration system was implemented on an ABB industrial robot IRB1600 successfully. And the joint offsets of this robot can be calibrated within 6 minutes.

1. Introduction

Industrial robots with better repeatability have been widely used over past decades. Positioning accuracy of industrial robots is not necessary in some point to point (PTP) applications because a sequence of points can be programmed by teaching pendant and replaying these points. However, as more and more industrial robots are used for more complicated workplaces, such as high precision assembly automation [1] and surgery [2], positioning accuracy of industrial robots becomes more and more important. There are several factors that can cause robot errors: environmental, parametric, measurement, computational, and application [3]. And robot calibration has been taken as an efficient way to improve its accuracy.

Different robot calibration methodologies and systems have been developed to improve the robot accuracy. At the beginning, people normally used open-loop methods with high precision equipment to measure the robot end-effector pose, such as coordinate measurement machines [4] and laser tracking system [5]. These measurements are expensive and time consuming and have to be performed regularly. Later, close-loop techniques based on joint angle sensing were developed, which use some constraints on the end-effector to form closed kinematic chains. Physical contact constraints, such as planar constraints [6, 7] and single endpoint constraint [8], on the end-effector suffer from inaccuracy positioning and time consuming. Nonphysical contact constrains usually depend on laser tools. Newman and Osborn [9] and Chen et al. [10] proposed calibration methods using laser line tracking. Their approach relies upon constraining the endpoint moving along a stationary laser beam. And the difficulty is to exactly and automatically fit the line constraint. Gatla et al. [11] described a virtual closed kinematic chain method. In order to create the virtual closed kinematics chain, a laser tool attached to the end-effector was aimed at two arbitrary but fixed points on some objects. The constrains were realized manually, but they pointed out that the system could be automated by a feedback system.

According to [12], more than 90% of the positioning inaccuracy issues of industrial robots are caused by the robot joint offset. In reality, different robot factories use different techniques to calibrate the kinematic parameters of their robots before delivering them to the customers. During the shipment and installation of the industrial robots for customers, link parameters and gearing errors do not change much, typically. However, joint offsets might be changed because of the assembly or the replacement of motors and encoders. Moreover, a small change of the joint offsets will affect the positioning accuracy significantly. Although some of the previous methods can be used to calibrate the robot joint offset, they are either costly or time consuming. It is essential to develop an efficient industrial robot joint offset calibration technique. To improve the efficiency of the calibration system, automation has to be considered. Currently, camera-aided or vision-based feedback system [1315] would be the best choice to realize automated calibration system.

Based on our previous work on automated robot calibration [1620], this paper presents a high efficient joint offset calibration system for industrial robots. The proposed method mainly depends on a laser pointer and a camera attached on the end-effector of industrial robot and a PSD-based device arbitrarily located in the work space of the industrial robot. A vision-based feedback system is used to bring the laser beam shooting onto the PSD surface. Then a PSD-based feedback system will be used to realize high precision positioning control. The automated calibration procedure consumes no more than 6 minutes and the time is mainly consumed by servo controlling the laser beam loaded by robot to shoot at the center of the PSD surface from various robot positions and orientations. Because of the high resolution of the PSD (0.1 μm), all the laser lines will shoot on the same point at a small range of error and a set of robot joint angles will be recorded. Based on the recorded joint angle and forward kinematics of the industrial robot, it is straightforward that if offset values of all joints are zero, the intersections of every laser line pair computed from the recorded joint angle and forward kinematics are the same point. However, if offset values of the joints are not zero, the intersections of every two lines combination will be different points. In other words, the distribution of the intersections of lines depends on the robot offset. An optimization model and algorithm have been formulated to identify the robot constant offset and LM algorithm was employed to solve the optimization problem and obtain the solution. Experiments on an ABB industrial robot IRB1600 have been performed and verified the feasibility of the proposed calibration system. And the new contribution of the work is that the developed calibration system is of low cost and is easy to set up and can calibrate the joint offset automatically and efficiently.

The rest of the paper is organized as follows. In Section 2, line-based and single point constraint approach for joint offset calibration methodology for industrial robots will be presented along with least square based joint offset identification. After that, several important characteristics, including uncalibrated laser tool, initial pose selecting, first joint offset, and key devices (laser and PSD), of the presented calibration methodology are discussed thoroughly in Section 3. Then, detailed automated calibration system and experimental results are illustrated in Section 4. Finally, our conclusions are presented in Section 5.

2. Calibration Methodology

We consider a typical industrial robot having six degrees of freedom (DOF) as shown in Figure 1. Without losing the generality, skeleton of an ABB robot IRB1600 is used. We employ and () to denote the joint angles and joint offsets, respectively.

Based on Denavit-Hartenberg (DH) convention, the homogeneous transformations are represented as where , and are generally named as link length, link twist, and link offset, respectively, and these parameters are taken as accurate in this application, and denotes and denotes . Once the joint offset exists, the above homogenous transformations can be rewritten as where The forward kinematics with the offset of the industrial robots is written as Now, we are going to develop a method to identify these constant joint offsets in the forward kinematics (4).

It is meritful to point out that the forward kinematics of industrial robots other than 6 DOF can be achieved similarly as (4). And also the joint offset calibration method presented in the following can also be generalized to any DOF industrial robots.

2.1. Line-Based and Single Point Constraint Approach

The novel industrial robot kinematics parameter calibration system using line-based and single point constraint (LBSPC) approach, as shown in Figure 2, was developed to calibrate the joint offsets. The proposed method relies mainly upon a laser pointer attached on the end-effector of a robot and single PSD. The laser pointer generates laser beams that can be expressed as lines in space. It is the reason we call it line-based. And the lines parameters are based on the robot configuration and the position of the laser pointer regarding the end-effector of the industrial robot. The calibration procedure is performed by pointing the laser beam at the same point, that is, the center of PSD surface, from the various positions and orientations. That is why we called it single point constraint. And the coordinates of the PSD in the robot base frame are unknown.

The laser beams can be guaranteed to shoot at the same point, that is, the center of the PSD, through PSD-based feedback aided by vision-based servo control [16]. The robot joint angles are recorded when each shooting at the center of PSD is achieved. Substituting the recorded joint angle into the forward kinematics with offset error (4), the homogeneous transformation of end-effector frame with regard to the robot base frame is given by It is obvious that the only unknown parameters are the joint offset in the above matrix.

The laser pointer is attached to the end-effector rigidly with a well-machined fixture. And the fixture is designed as a calibration reference attached to the end-effector; therefore the detailed configuration and dimension are known. As a result, the parameters of a laser line as shown in Figure 2 are known with regard to the end-effector frame: where is the coordinates of one point of the laser line in the end-effector frame and is the unit vector of the laser line orientation in the end-effector frame. If we take the laser pointer and its fixture as a tool, the homogeneous transformation is known (for unknown calibration tool, we will discuss it in the next section). Now, by combining the tool parameters and (5), one of the laser lines as (6) translated from end-effector frame to robot base frame can be described by where is the coordinates of one point of the laser line in the robot base frame and is the unit vector of the laser line direction in the robot base frame.

It should be reminded that all the lines (7) do actually go through the same point, the center of PSD surface. Based on the line equations and single point constraint, we are ready to identify the joint offset .

2.2. Joint Offset Identification

As sets of joint angles are recorded after the procedure of locating the laser beam at the center of the PSD surface, we have laser lines. Let denote the th laser line, let denote the intersection or the center of the shortest distance between and (where , , , and is the number of the intersection or the center of the shortest distance of each two lines among the lines; thus ), and let denote the mean point of the total intersections . The coordinate errors of the points between and are denoted as , , in the , , directions, respectively. The parameters of joint offset are identified by minimizing the total sum of the squares of the coordinate errors

Note that the average point is updated during the minimization iteration process and is the center of the line which is the shortest distance between lines and if the two lines do not have an intersection. It is straightforward that the intersections of every pair of laser lines computed from the recorded joint angle and forward kinematics are the same point if offset values of all joints are zero. However, if offset values of all joints are not zero, the intersections of every pair of laser lines are different points. In one word, the distribution of the intersections depends on the robot offset. The idea of the identification can be illustrated as in Figure 3.

The method for the nonlinear optimization is iterative. For this nonlinear square problem, LM algorithm [21] is applied to solve the optimization problem and obtain the solution. This optimum algorithm is a damped Gauss-Newton method based on the Jacobian and damping parameter . The step is defined by where.

3. Discussions

According to the above industrial robot joint offset calibration scheme, there are several important issues needed to be discussed.

3.1. Uncalibrated Laser Tool

A laser tool consisting of a focusable laser pointer and its adapter is rigidly attached to the end-effector of the robot. In the last section we suppose that the laser tool is well calibrated because it is designed as a calibration reference. And then all the parameters and in (6) are known in end-effector frame. If this laser tool is not calibrated, it still can be used to calibrate the joint offsets of the industrial robot.

Suppose the laser line is adjusted to roughly align its orientation to one of its axes which is toward the PSD surface in the end-effector frame (such as -axis). Once the laser pointer and the adapter are fixed, the laser line in the end-effector frame can still be represented by (6). The difference is that the values of and are unknown this time. Notice that, the three unit direction vectors are dependant The parameter is the offset along the -axis in the end-effector frame and it is selected as . Thus, we have four independent parameters of the laser line . It also should be noted that the last joint (joint 6) is dependent on the parameters of the laser line now. In this case the identified offset of joint 6 is meaningless. Therefore, compared to the calibrated laser tool case, we have three more parameters needed to be identified. And the cost function (8) is revised to Using the same LM algorithm, the laser line parameters and the joint offset can be identified based on enough recorded sets of joint angles under single point constraint.

As a conclusion, zero joint offset angles can be calibrated even when the laser tool is not calibrated in advance.

3.2. Initial Postures Selecting

The idea of the developed calibration procedure is aiming a laser beam from the laser pointer at the same point from various initial postures, that is, positions and orientations, as shown in Figure 2. The same point is the center of the PSD surface, and the merit is that the PSD can be put arbitrarily in the work space of the robot; that is, the coordinates of the point in the robot base frame are unknown. Here we will discuss two typical path planning schemes during the calibration procedure. One is aiming the laser at the point from right side of the PSD to left side (along -axis direction in robot base frame as shown in Figure 2) called Y-Pattern. And the other one is aiming the laser at the point from the back side to the front side (along -axis direction in robot base frame as shown in Figure 2) called X-Pattern. These two typical calibrating path planning schemes render different initial postures. Therefore, the recorded robot configurations during the calibration procedure with these two patterns will be different. We will now discuss how the different patterns of calibration procedure affect the calibration result.

Based on the feedback control, the laser beam was precisely aimed on the center (unknown position) of the PSD with X-Pattern or Y-Pattern. Then sets of joint angles are recorded, and LM is employed to identify the parameters. The convergent step is determined by (9) and is sensitive to the Jacobian (note that it is different from manipulator Jacobian which is determined by (8) or (11)). The position of PSD and the calibration pattern play an effect on the Jacobian. We will prove it mathematically based on the relationship between the change in the intersection of two laser lines and the variation of joint angles. Without loss of generality, assume aiming a laser beam at the same point from two positions and . Accordingly the joint angles are recorded as and , respectively. Let the coordinates of in the base frame be . Substituting the joint angles into (5) and the point with different orientations can be represented by where denotes the transformation matrix of the laser spot frame with respect to the end-effector frame. Let denote the transformation matrix of the laser spot with respect to the joint 2 frame. Then at the positions and , can be represented as Consider the same point constraints at these two positions; we have [17] If the center of PSD locates on the -axis in the base frame, then , and if X-Pattern is used, then . And then the above equations can be rewritten as Calculating , we have The same result exists when joint 2 has a variation that can be taken as the zero offset . Consequently, the cost function (8) (or (11)) used to identify the parameters is independent of the offset of joint 2; therefore it cannot be identified.

Furthermore, if and X-Pattern is employed, then , . The cost function will be unsensitive to the offset of joint 2. If there are some noises added to the joint angles, the real parameters are difficult to be identified because of local minimum. Even if is not close to zero, the change of joint 1 angle is very small under the X-Pattern, and the joint 1 angle is close to a constant. Thus it still suffers from similar result. However, it is free from the issue under Y-Pattern because the joint 1 angle changes a lot.

As a conclusion, inappropriate initial postures selected for calibration could lead to failure of joint offsets identification. Various postures with obvious angle changes of each joint for the calibrating robots should be beneficial to identify joint offsets. To enhance the efficiency of the calibrating process, successive types of postures are preferential. In our implementation of the calibration, the Y-Pattern was selected.

3.3. Joint Offset

Based on the calibration methodology proposed in the last section, one can only get the slope of the line, not the absolute position of the line due to the line fitting method. Therefore, the calibration method based on the straight line cannot be used to identify the zero offset of joint 1. This is the limitation of the method. However, the joint 1 angle offset is not so important because it defines the robot base frame. If the robot base frame rotates, other frames can be calibrated based on the rotated base frame. Therefore, the provided method is enough to improve the robot accuracy.

3.4. Laser Pointer and PSD

The proposed line-based and single point constraint joint offset calibration scheme is related to two main devices. One is the laser pointer used to generate a laser line and the other is a PSD whose surface center is taken as the constraint point. A PSD is a sensor capable of tracking the location of a light beam on its surface. It consists of either one or two resistive layers (corresponding to one-dimensional or two-dimensional PSD) placed on the surface of a high-resistive substrate. There are basically two types of PSD which are produced by various manufacturers worldwide: lateral PSD and segmented PSD [16]. Both types are produced in both one-dimensional and two-dimensional versions. Because we use the PSD as a sensing device to position a point on its center point, two-dimensional PSD is required. The resolution of current two-dimensional PSD is better than 0.1 μm in each direction. It is qualified as a point constraint device to calibrate industrial robots. Based on the operation principle of PSD, the generated electric charge is proportional to the light intensity stimulated with the laser beam. Therefore, it is essential to use a high quality laser pointer generating laser beam with unchanged light intensity during calibration procedure.

4. Implementation

4.1. System Description

The hardware overview of implementation of the robot calibrations system is shown in Figure 4. The system mainly consists of an ABB 6-DOF robot IRB1600 and its controller ABB robot controller IRC5, two PCs (personal computers), a focusable laser pointer, a CCD (charge coupled device) camera, and a portable PSD-based device.

Industrial Robot. An ABB 6-DOF industrial robot IRB1600 was employed in the implementation. The DH parameters of the robot as the factory design were listed in Table 1.

Portable PSD-Based Device. The portable PSD-based device, as shown in Figure 4(d), is specially featured as follows.(i)Portable: the size of the portable PSD-based device is 4.75 × 5 × 4 (inch).(ii)Low cost: only one PSD is used, which is no more than 100 dollars.(iii)Easy installation and operation: it is wireless and can be arbitrarily located on the workcell.

There are no signal and power cables to be connected from the portable PSD-based device. The PSD and its data acquiring system, battery, and wireless USB (universal serial bus) hub for data communicating with the main PC-based controller are well constructed and organized. Two LEDs (light emitting diodes) are used as markers to facilitate vision-based servo control.

Laser Pointer. The focusable laser pointer and its fixture rigidly attached to the end-effector of the robot, as shown in Figure 4(c), are used to shoot a high quality laser beam onto the surface of the PSD.

CCD Camera. The camera and vision-based servo control are to improve the level of calibration automation. The camera can aid the robot in finding the location of the PSD efficiently [16, 19]. A frame grabber board connected to the CCD camera is used to capture the image.

LAN-Based Control System. A PC-based main controller has been developed for the calibration system. Feedback PSD information is collected based on the wireless USB interface. Feedback processed vision information is collected from the image processing PC via LAN- (local area network-) based communication. The main controller PC can obtain the current status from and send the generated commands to the robot controller (ABB robot controller IRC5) via LAN communication. This LAN-based close-loop control system can bring the laser beam to the center of the PSD from different initial postures of the robot efficiently.

Automated Calibration Process. The flowchart of the developed automated calibration process for industrial robots joint offsets is shown in Figure 5. At the beginning of the automation calibration, several initial postures of the robot are generated. Once the LAN-based control system brings the laser beam to the center of the PSD, the joint angles of the robot are recorded. Once the planned shooting times are finished, the joint offsets can be identified immediately. In our implementation, 7 Y-Pattern initial postures were planned, and the overall automated calibration process cost no more than 6 minutes.

4.2. Experimental Results

Three sets of experimental result on proposed joint offsets calibration with the above implementation system are shown in Table 2. One can see from Table 2 that the standard deviations of the joint offsets are no more than 0.09, which demonstrates the stability of the proposed joint offsets calibration technique. What is more, each automated calibration experiment took no more than 6 minutes. Comparing to the calibration with only position measurement proposed in [22], in which only collecting position data will cost about 20 minutes, the proposed joint offsets calibration system proposed in this paper for industrial robots is more efficient.

5. Conclusions

This paper presents an efficient joint offset calibration system to improve the positioning accuracy for industrial robots. Line based and single point constraint calibration methodology is provided. Several important issues of the methodology are discussed in detail. Automated calibration system based on PSD and vision feedback was developed. And experiments implemented on an ABB industrial robot verified the feasibility and effectiveness of the proposed method and the developed system.

Comparing to previous calibration methods on joint offset of industrial robot, the affordable and portable calibration device and totally automated calibration process are the main advantages of the proposed scheme in this paper.

Conflict of Interests

The authors declare that there is no conflict of interests regarding the publication of this paper.

Acknowledgments

The first author would like to express his thanks for the financial support from the National Science Foundation of China (NSFC) with no. 11102039 and the Opening Fund of Jiangsu Key Laboratory of Remote Measurement and Control Technology with no. 7722009001. The second author would like to express his thanks for the financial support from National Natural Science Foundation of China (NSFC) under Grant 61175082, Jiangsu Prospective Joint Research Project under Grant BY2013046, and Lianyungang Prospective Joint Research Project under Grant CXY1310.