Abstract

A method with easy operation procedure and simple calibration condition is presented in this paper to solve the base frame calibration problem for cooperative robots. It is carried out through constructing a series of handclasp configurations and recording coordinates of the contact points, respectively, in base frame of each robot. Then the rotation matrix and translation matrix between base frame of cooperative robots can be calculated which is just the calibration result for cooperative robots. Based on typical installation mode for industrial robot, the floor mounted, wall mounted and ceiling mounted, constraints between base frames of these robots are further explored. These constraints are used to improve the calibration results for base frame calibration problem. In order to validate the correctness and effectiveness of our method, experiments on two industrial robots (Motoman VA1400 and HP20) are carried out at the end of the paper. The calibration errors are less than 8 mm in most cases, which satisfies the requirement of positioning accuracy for most industrial process, such as arc welding, transporting, and cutting. These experiment results assert the correctness of our method which can be used effectively to solve the base frame calibration problem for cooperative robots in manufacturing process.

1. Introduction

Cooperative robot system is a hot topic in robotics and much literature has been reported in this field. A multiple robot system surpasses a single robot system greatly in terms of flexibility and versatility in task execution. Particularly, multiple robot cooperation is required if we are to assemble and manipulate parts without the aid of fixtures or jigs or if we to smoothly transfer heavy and voluminous objects from one place to another. In the case of cooperation control between two robots, one robot must be informed of the position and orientation of the other robots. Therefore, robot base frame between one and another must be calibrated out before the cooperation starts. This paper aims at presenting an effective solution to such a problem of base frame calibration between two cooperative robots.

“Base frame calibration, which is to determine the relative translation and rotation between base frames of two cooperative robots, is a challenging and basic problem for multiple robot system. A direct measurement is unaccessible because origins of the robot base frames are out of reach. Calibrations for an individual robot have already been investigated extensively and many effective methods have been developed [13]. Nevertheless, few researches have been made on calibration problem between two robots. Reference [4] proposed a passive base frame calibration method for two cooperative industrial robots by using a series of “peg-into-hole” manipulations to set up the calibration equation as . The calibration accuracy depends on how precisely the peg aligned with the hole, which is monitored and adjusted manually by human operator. Through a hand-mounted vision sensor, a more human-independent calibrating approach for dual robots system is presented in [5]. It takes advantage of relative motion between the robot end-effectors which can be recorded by the vision sensor to calculate the transformation relation between the base frames of dual robots. However, vision sensor parameters and their mounted postures are required for calculation of the transformation. Therefore, calibration result would be poor if these prerequisites were unprecise. Reference [6] introduced another calibration method based on Direct Linear Transformation using two CCD (Charge Coupled Device) cameras for cooperative industrial robots. Without knowing the mounting information of the cameras, it just uses a set of motions commanded to each manipulator. By detecting the motion with the cameras, relative rotation and translation between base frames of the two robots can be obtained. A simpler but more effective calibration method is presented in [7]. It uses only two calibration plates which are inexpensive to manufacture and requires no other measuring instrument. Only by forming the cooperative manipulators into a closed chain, commanding them to move through a set of postures and recording the joint information, the calibration problem can be formulated as a nonlinear optimization problem.” (This paragraph is cited from our previously published paper in [8]. It has been included in this paper just for integrity reason.)

In one of our previous works [8], a new calibration method based on handclasp manipulation is proposed. This method uses only a series of handclasp manipulations and their corresponding joint information to calculate the transformation relation between base frames of the cooperative robots. No external calibration apparatus or elaborate setups are needed. Great advantages of this method are the easy operational procedure and simple calibrating condition, which makes it quite feasible for use in manufacturing field, whereas the calibration problem considered in [8] is a generic form. For industrial process, robot base installation has strong characteristics. These characteristics can be described by a concept of robot installation angle. Definite constraints exist between robot installation angle for typical installed robots. Considering these constraints, the calibration results in [8] can be greatly improved for typical installed robots. Therefore, further research has been conducted to improve the calibration accuracy of our previously proposed calibration method. Focus of the innovation in this paper lies in that constraints between robot installation angles for typical installed robots have been involved in the calibration process, which improves the calibration accuracy a lot. Remainder of this paper is organized as follows. Section 2 introduces theoretical analysis of the improved method for robot base calibration. Section 3 presents the calibration procedure of this method. In addition to the method introduction, calibration experiments for two cooperative industrial robots are presented in Section 4. Concluding remarks follow in Section 5.

2. Method of the Calibration

2.1. Robot Installation Angle

In applications with a single robot, the world system is usually chosen in the base of the robot. Yet, when several robots work together in a task, it is beneficial to use a world system independent of the individual robots. To enable this, the path controller has to manage the position of the individual robots in the world system by defining a separate robot base frame.

For most industrial applications, only three installation types exist for the robot base mounting, which is called floor mounted, wall mounted, and ceiling mounted. For quantitative descriptions of the aforementioned robot base installation types, concept of robot installation angle is defined as follows.

Definition 1. As shown in Figure 1, the installation angle is defined as the joint between axis- of robot base frame and the ground level line.

Since the definition of robot base frame has a unique form in industry standard [9], the above definition of the robot installation angle is invariant with respect to the robot’s front and rear. For further illustration, examples of typical installation angle are shown in Figure 2.

By the definition of robot installation angle, a floor mounted robot has an installation angle of , a wall mounted robot has an installation angle of or , and a ceiling mounted robot has an installation angle of . Introducing these values to base frame calibration between typical installed robots, the calibration results will be improved greatly compared with the calibration results presented in [8].

2.2. Calibration of Generally Installed Cooperative Robots

In [8], we proposed a base frame calibration method for generally installed cooperative robots. Principle of the calibration method in [8] is used as the development basis for this paper.

For two cooperative robots as shown in Figure 3, is the base frame system for robot Motoman VA1400 and is the base frame system for robot Motoman HP20. These two robots form a handclasp configuration in Figure 3 with measuring tips mounted at the end of each robot. Let the homogenous matrix be the relative position and orientation between these two robots. can be calibrated by 4 handclasp manipulations as shown in Figure 3.

Reference [8] presents basic forms of the base frame calibration equations for two cooperative robots. Those equations are generic forms. For typical installed robots, those equations can be refined to improve the calibration results as discussed in the next part of the paper.

2.3. Calibration Equations for Typical Installed Robot

In this paper, only three types of the robot base installation are considered, which are floor mounted, wall mounted, and ceiling mounted. Thereafter, only three types of the robot base calibration problems are considered here, which are calibration of a floor mounted robot to a floor mounted robot, calibration of a floor mounted robot to a wall mounted robot, and calibration of a floor mounted robot to a ceiling mounted robot. Although the resulting classification is not exhaustive, it covers most cases of the industrial applications.

2.3.1. Calibration of a Floor Mounted Robot Relative to a Floor Mounted Robot

As shown in Figure 4, a floor mounted robot is carrying out the handclasp manipulation with a floor mounted robot. By the above introduced method, relative position and orientation between base frames of the two robots can be calibrated. Theoretically speaking, the rotation matrix for orientation between the two base frames must be orthogonal and normalized, whereas the solution cannot ensure this characteristic, because resolution of transducer for robot joint positions is limited and error exists in system modeling. Therefore, an orthonormalization procedure is necessary to refine the calibrated result for frame rotation.

The criterion for rotation matrix orthonormalization is that modification made on frame rotation must be the least. The Frobenius norm of matrix is adopted to evaluate the difference between two matrices, which is where is an matrix, . By the Frobenius norm, a cost function for the orthonormalization can be defined as The Frobenius distance between and is adopted as the cost function because each element difference will contribute to the increase of matrix distance. The Frobenius norm is much more sensitive to the element variation than other matrix norms. When is minimized, it means that each element variation between and is averagely minimized. Let be the orthonormalized result; we have Equation (3) means orthonormal matrix is the optimal Frobenius norm approximation for preliminary solution .

For the calibration case in Figure 4, relative orientation between the two cooperative robots exists in the form of a rotation around axis- of the robot base frame. Since the two robots have the same installation angle of , rotation matrix between their base frames and will be where is an arbitrary angle.

Let ; then . Substituting into (2) yields Equation (5) can be viewed as a mathematical optimization problem, which is to find the minimum of a multivariable function subject to constraint . The method of Lagrange multipliers [10] provides an effective strategy for solving these problems. Define the Lagrangian function as Let the preliminary calibration result be Substituting (7) into (6) and expanding the function yields

Minimizing the function (8) with respect to , and , we obtain Unique solution exists for (9); that is,

After are obtained, we have the refined calibration result for rotation as

in which is the orthonormalized and refined calibration result for rotation matrix. Thereafter, the translation vector also needs to be recalculated, which is

Equations (11) and (12) are developed form of the calibration equations in [8], which will lead to more accurate calibration results compared with other methods as presented in [8].

2.3.2. Calibration of a Floor Mounted Robot Relative to a Wall Mounted Robot

As shown in Figure 5, a floor mounted robot is carrying out the handclasp manipulation with a wall mounted robot. For the calibration case in Figure 5, relative orientation between the two cooperative robots exists in the form of 3 successive rotations.

(I) A rotation of angle for Robot HP20 around axis- of the robot base frame to make axis- of horizontal, which is

(II) A rotation of for Robot HP20 around axis- of the robot base frame to make axis- of vertical to the ground, which is

(III) A rotation of angle for Robot HP20 around axis- of the robot base frame to make axis- of stretch along the same direction as axis- of , which is

By (13), (14), and (15), we have the rotation matrix between robot base frame and as

For simplicity, let ; then , Substituting (17) into (2) yields Equation (18) also is a multivariable function optimization problem. By Lagrange multipliers method, define the Lagrangian function as Substituting (7) into (19) and expanding the function yields

Minimizing the function (20) with respect to , and , we obtain Collectively, there are 6 unique equations in (21) totaling the number of elements in function (20). Therefore, unique solution exists for (21), which can be reached by Levenberg-Marquardt method with a numeric iterative procedure.

After , and are obtained, an orthonormalized and refined calibration result for rotation matrix can be obtained by (17). Thereafter, the translation vector also needs to be recalculated as (12).

2.3.3. Calibration of a Floor Mounted Robot Relative to a Ceiling Mounted Robot

As shown in Figure 6, a floor mounted robot is carrying out the handclasp manipulation with a ceiling mounted robot. For the calibration case in Figure 6, relative orientation between the two cooperative robots exists in the form of 2 successive rotations.

(I) A rotation of for Robot HP20 around axis- of the robot base frame to make axis- of vertical to ground, which is

(II) A rotation of angle for Robot HP20 around axis- of the robot base frame to make axis- of stretch along the same direction as axis- of frame , which is

By (22) and (23), we have the rotation matrix between robot base frame and as Let ; then , Substituting (25) into (2) yields Equation (26) also is a multivariable function optimization problem. By Lagrange multipliers method, define the Lagrangian function as

Minimizing the function (27) with respect to , and yields Unique solution exists for (28); that is, After are obtained, we have the refined calibration result for rotation as

in which is the orthonormalized and refined calibration result for rotation matrix. Thereafter, the translation vector also needs to be recalculated as (12).

Equations (30) and (12) are developed form of the calibration equations in [8], which will lead to more accurate calibration results compared with other methods as presented in [8].

3. Calibration Procedure

Base frame calibration between two cooperative robots is to identify elements of a rotation matrix and translation vector . Information that we need for our calibration method includes robot joint positions, robot link parameters, and measuring tip dimensions. Preparatory conditions for this calibration method are quite simple, which include only the installation of the measuring tips on both robots and dimensions input of the measuring tip for each robot.

After commencing of the calibration command, move one robot to an arbitrary position. Align the tool center point of the other robot to tool center point of the first robot by independent robot motion. The two robots form a handclasp configuration and the first measurement commences. Register the position as . Repeat this handclasp manipulation process three more times and register , , and in the same manner as . Both robots are to be moved independently during the calibration procedure. After , and are registered, substitute these points information into corresponding calibration equations. For calibration of floor mounted robot relative to floor mounted robot, the calibration equations are (11) and (12). For calibration of floor mounted robot relative to wall mounted robot, the calibration equations are (17) and (12). For calibration of floor mounted robot relative to ceiling mounted robot, the calibration equations are (30) and (12). Figure 7 shows the calibration procedure of our proposed method.

In order to optimize the calibration results, the handclasp points selected should be as far apart as possible. The standard distance between and and , and and should be 1 m or more. Typical selection of these 4 points is shown in Figure 8. As shown in Figure 8, teach , and so that a triangle, not a straight line, is formed. Teach far apart from planar so that a triangular pyramid is formed. Otherwise, inaccurate calibration will result.

After the calibration procedure, a check should be made to see if the two robot base frames are correctly calibrated. Jog the two robots in a coupled synchronous motion [11] and move one of them to see if the other can follow the motion of the first robot. If yes, base frames of the two robots are correctly calibrated.

4. Experiment Result

In order to validate the above-proposed calibration method for typical installed robot, representative experiments have been carried out in our lab. The testbed is composed of two industrial robots, Motoman VA1400 and HP20, which are produced by YASKAWA Electronic Corporation, Japan. An external PC, DELL Optiplex 780, is used as a top layer controller to implement all the control logic and calculations. This external PC is connected to the robot controller DX100 by Ethernet cable. The communication software MotoCom SDK, which is also provided by YASKAWA Electronic Corporation, is installed on the PC to help transfer robot data and job files between the PC and DX100 robot controller. Figure 9 shows the experimental testbed we used here in our lab.

By the communication software MotoCom SDK, user applications can be developed and executed on a PC platform. MotoCom SDK provides users with the function to obtain coordinate of robot tool center point in its base frame, which forms the source data of calibration in the following analysis. Coordinate of robot tool center point in its base frame can be directly read out from the robot controller DX100 by function BscIsRobotPos( ), which is one of the member functions provided by MotoCom SDK, whereas MotoCom SDK only provides a 6-dimensional vector to represent position and orientation of the robot end-effector, 3-dimension for tool center point position and 3-dimensional Euler angles for tool orientation. The variables , and have a unit of millimetre while variables , and have a unit of degree . These coordinate values can also be found on the teaching pendant of the robot controller.

For consistency and coherence, transformations between Euler angle representation and a rotation matrix are presented here. In [12], successive rotations with angle relative to axis will lead to a rotation matrix represented in (31) as follows:

Conversely, a rotation matrix can be decomposed into three successive rotations with relative to axes ,

Equation (32) will encounter degeneracy when or . However, when or , it means and . In such a case, we arbitrarily assume . When or , we assume . Under this assumption, (32) is qualified for the rotation error assessment.

The 6-dimensional vector formation is also adopted to represent the relative translation and rotation between based frames of the two robots. The aforementioned 3-dimension vector indicates relative translation and 3-dimensional vector Euler angles indicate relative rotation. The variables , and also have a unit of millimeter (mm) while variables , and have a unit of degree .

For accuracy assessment, the calibration error for relative rotation between the two robots can be defined as in which is true values of the Euler form rotation between the two robots and is the error. The error with a unit of degree has a definite meaning that represents the maximum error between Euler angle forms of the calibrated rotation matrix and its true value. The calibration error for the translation vector can be defined as in which is true values of translation vector between the two robots and is the error. The error has a unit of millimeter (mm), whose meaning represents the maximum error between calibrated translation vector and its true value.

True values for relative rotation and translation between base frames of the two robots are calibrated by an external sensor Actiris350. The Actiris350 system is a 3D coordinate measuring machine manufactured by ActCM Corporation, France. Actiris350 system has a precision of ±15 μm for single point according to ISO 10360-2; repeatability is ±25 μm, acquisition speed is 15 measurements per second max, and measuring volume is 3.5 m3. Figure 10 shows the 3D coordinate measuring machine Actiris350 we used.

Table 1 presents the robot base calibration results and comparisons with other methods. Data in column are the true values of the relative rotation and translation between base frames of Motoman VA1400 and HP20, which are acquired by Actiris350, . Data in column are the calibrated results by our proposed method, . The columns obtained by (34) and obtained by (33) are the calibration errors of robot base frame translation and rotation, respectively, for this method. Data in column are calibration results by the method proposed in [8]. The columns obtained as and obtained as are their calibration errors for robot base frame translation and rotation, respectively. Figure 11 shows the calibration error and for relative translation between the two robots. Figure 12 shows the calibration errors and for relative rotation between the two robots.

As shown in Figures 11 and 12, it is clear that the calibration accuracy by our proposed method is no more than 8 mm for relative translation and for relative rotation, which indicates that calibration errors are relatively small. This precision level is quite satisfactory that can meet the requirement for most rough robot tasks, such as spraying, arc welding, or material transportation. So far, it can be concluded that the calibration method proposed in this paper is quite effective to solve the problem of base frame calibration for two cooperative robots.

5. Conclusion

A simple but effective method for calibrating the relative rotation and translation between base frames of two cooperative robots is presented in this paper. Greatest advantage of this method lies in its simple calibration setup and no other measuring apparatus required, which makes it quite feasible for applications in manufacturing works. The calibration procedure is based on a series of handclasp manipulations. Robot base installation angles are adopted to refine the preliminary calibration result.

Experimental testbed of base frame calibration with two cooperative industrial robots Motoman VA1400 and HP20 is presented here. Calibration results are quite satisfactory which asserts the validity and effectiveness of this method. The only defect of this calibration method may lie in that the handclasp manipulation for cooperative robots is driven by human operator. If the tool center point of each robot cannot be exactly driven to one same point, error will expand in the calibration result, whereas as long as the human operator drive the robot carefully and make the handclasp manipulation as accurate as possible, the calibration error can be reduced to relatively small.

Conflict of Interests

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

Acknowledgments

This work was supported by the National Natural Science Foundation of China under Grant no. 61175113, National High Technology Research and Development Program of China under Grant nos. 2009AA043903-1-1 and 2007AA 041703, Research Innovation Program for College Graduates of Jiangsu Province under Grant no. CX10B_076Z, and Scientific Research Foundation of Graduate School of Southeast University under Grant nos. YBJJ1029 and YBPY1302.