Keywords

1 Introduction

The traditional application areas for industrial robot involve tasks that require good repeatability but not necessarily good accuracy such as handling, assembly, painting and welding. Compared with CNC machine tools, industrial robots have the advantages of wider workspace, lower cost and greater flexibility, thus can offer an efficient solution for large and complex shaped product manufacturing in aerospace industry [1]. Robot machining has become a significant trend in manufacturing industry, and many researches have been conducted in this area [2].

However, industrial robots are still rarely used in milling applications in industry. Except for the inherent low absolute accuracy and stiffness characteristics of industrial robots, the lack of a standard post-processing software is the main obstacle. This paper aims to solve this problem. In milling application, the robot cutting trajectory is usually converted from cutter location (CL) data generated by a 5-axis milling module in a commercial CAD/CAM software package [3]. Nevertheless, a milling task only requires five degrees of freedom (DOFs), three of which are used to locate the tool center point (TCP) and the rest two are used to determine the tool axis direction, while a standard commercial industrial robot usually has 6 DOFs. Using a 6-axis industrial robot to perform 5-axis milling tasks will result in one redundant DOF, which is the rotation about the milling spindle axis. This is a common situation because that the spindle axis is often mounted not to be aligned with the last joint axis to improve the dexterity and manipulability of the robot [4].

Until recently, a lot of researchers have been working on optimizing the redundant DOF and introducing new methodologies into the post-processor of a cutting robot. Xiao et al. [4] propose an optimization method which simultaneously optimizes the robot singularity criteria, joint limit criteria and obstacle avoidance criteria via one-dimensional search. Laurent et al. [5] and Huo et al. [6] use the Moore-Penrose pseudo inverse with an optimization term to solve the redundancy problem considering a set of performance criteria of the robot including joint limits, singularity avoidance and so on. These researches mainly concentrate on the geometrical and kinematical constraints of the robot, while neglect the machining performance in milling process. In milling operations, insufficient stiffness of the robot will cause static deformation of the TCP and vibrations of the robot structure [7], which will degrade the machining quality significantly. Therefore, some stiffness-based performance indexes have been proposed to optimize the redundant DOF in machining applications. Angeles [8] suggests the norm of the Cartesian stiffness matrix would be a plausible candidate. While Guo et al. [9] point out that the norm makes no physical sense as the Cartesian stiffness matrix has entries with disparate physical units, and they propose a performance index in terms of the determinant of the translational compliance sub-matrix (TCSM). However, this performance index just describes the overall stiffness of the robot at a certain posture, and doesn’t pay enough attention to the anisotropy of the Cartesian stiffness [10]. In milling applications, the stiffness of the TCP along certain directions is usually paid special attention. Peng et al. [11] suggest that the feed-direction stiffness should be maximized in their 7-axis 5-linkage machine tool, which guarantees a high machining efficiency via adopting a larger feed rate. This concept can be extended to robot milling, in which the process parameters such as feed rate and cut of depth are always conservative due to the low stiffness of the robot [12]. In this paper, a feed-direction stiffness based performance index is proposed to optimize the redundant DOF for robot milling. This index takes the anisotropic force ellipsoid of the TCP into account and will improve the production efficiency of the robot machining system.

The remainder of this paper is organized as follows. In Sect. 2, the mathematic formula of the redundant problem is derived. In Sect. 3, the stiffness model of a MOTOMAN MH80 industrial robot is identified. In Sect. 4, a new performance index for optimizing the redundant DOF is proposed. In Sect. 5, Experiments have been done to verify the effectiveness of the proposed method. The paper is concluded in Sect. 6.

2 The Redundancy in Robot Milling

The most important part of post-processing for robot machining is to determine the joint space, i.e. the set of revolute joint variables \(\theta _i (i=1,\dots ,6)\), from the CL data CL(xyzijk), where (xyz) is the coordinate of the TCP, while (ijk) is a unit vector representing the tool axis direction. Practically, the CL data is generated in a standard CAD/CAM software such as NX, the positions and orientations are all described in the workpiece frame. When the CL data CL(xyzijk) is obtained, the posture of the end effector (EE) of the robot with respect to the workpiece frame can be determined, and it can be represented by a six-dimension vector, namely \((x,y,z,\alpha ,\beta ,\gamma )\), where \(\alpha \), \(\beta \) and \(\gamma \) are the z-y-z type Euler angles. Knowing the posture of the EE, the robot joint angles can be finally calculated via inverse kinematics.

Let a frame attached to the cutter with its origin at the TCP and its axis along the tool axis is described by a six-dimension vector \((x,y,z,\alpha ,\beta ,\gamma )\) with respect to the workpiece frame, and the corresponding homogeneous transformation matrix \({}^w\mathbf {T}_t\) will be

$$\begin{aligned} {}^w\mathbf {T}_t=rot(z,\alpha )rot(y,\beta )rot(z,\gamma )trans(x,y,z) \end{aligned}$$
(1)

where rot and trans are rotation and translation transformations. So to perform a milling task, the CL data CL(xyzijk) and \({}^w\mathbf {T}_t\) have to satisfy

$$\begin{aligned} \begin{bmatrix} i&x\\ j&y\\ k&z\\ 0&1 \end{bmatrix} ={}^w\mathbf {T}_t\begin{bmatrix} 0&0 \\ 0&0 \\ -1&0 \\ 0&1 \end{bmatrix} \end{aligned}$$
(2)

It can be deduced from (1) and (2) that

$$\begin{aligned} \begin{bmatrix} i&j&k \end{bmatrix} ^T= \begin{bmatrix} -cos\alpha sin\beta&-sin\beta sin\alpha&cos\beta \end{bmatrix} ^T \end{aligned}$$
(3)

Equation (3) shows that given a CL point CL(xyzijk), five components of the six-dimension vector \((x,y,z,\alpha ,\beta ,\gamma )\) can be determined, i.e. \((x,y,z,\alpha ,\beta )\), while the third Euler angle \(\gamma \) is arbitrary, so that infinite robot configurations can be chosen to produce the specified CL. The redundant third Euler angle \(\gamma \) should be optimized.

The post-processing problem can be finally formulated as

$$\begin{aligned} \mathbf {\uptheta }(CL,\gamma )=f(CL(x,y,z,i,j,k),\gamma ) \end{aligned}$$
(4)

where \(\mathbf {\uptheta }=[\theta _1,\dots ,\theta _6]\) represents the robot configuration, and \(f(\cdot )\) denotes the inverse kinematics of the robot. For a standard six revolute joints industrial robot with the last three joint axis lines intersecting at a common point, analytical inverse kinematic solutions can be easily deduced [13].

To conclude, the key of the post-processing problem for a milling robot is to find a proper milling performance related index H to optimize the third Euler angle \(\gamma \), and determine a unique optimal set of \(\mathbf {\uptheta }\), i.e. the robot configurations along the milling path for a given set of CL data.

3 Stiffness Model and Its Identification

A robot deforms under external forces because of insufficient stiffness, thus the stiffness characteristic of the robot has a significant influence on the milling performance. The optimizing index should consider the stiffness model of the robot. Generally speaking, the robot stiffness mainly depends on the torsional stiffness of the gearbox and the drive shaft of each joint, the links are assumed to be infinitely stiff. Therefore, each joint of the robot is usually modeled as a linear torsion spring, and a constant diagonal matrix with each diagonal term defining the stiffness of a joint is used to represent the robot joint space stiffness characteristic [14, 15], i.e.

$$\begin{aligned} \mathbf {K}_\theta =diag([K_{\theta _1},K_{\theta _2},K_{\theta _3},K_{\theta _4},K_{\theta _5},K_{\theta _6}]) \end{aligned}$$
(5)

The Cartesian Stiffness of the EE is

$$\begin{aligned} \mathbf {K}_x=\mathbf {J}^{-T}_F(\mathbf {K}_\theta -\mathbf {K}_c)\mathbf {J}^{-1}_x \end{aligned}$$
(6)

where \(\mathbf {J}_x\) and \(\mathbf {J}_F\) are the Jacobian matrixes which satisfy \(d\mathbf {x}=\mathbf {J}_xd\mathbf {\uptheta }\) and \(\mathbf {\tau }=\mathbf {J}^T_F\mathbf {F}\), \(\mathbf {F}\) denotes the six-dimension wrench vector applied at a certain point on the EE, \(\mathbf {\tau }\) denotes the torques on the joints caused by \(\mathbf {F}\), \(d\mathbf {\uptheta }\) denotes the elastic deformations of the robot joints caused by \(\mathbf {\tau }\), and \(d\mathbf {x}\) denotes the six-dimension Cartesian deformations of the EE and it is measured at a point different from the force bearing point. \(\mathbf {K}_c=[\frac{\partial \mathbf {J}^T}{\partial \theta _1}\mathbf {F},\frac{\partial \mathbf {J}^T}{\partial \theta _2}\mathbf {F},\frac{\partial \mathbf {J}^T}{\partial \theta _3}\mathbf {F},\frac{\partial \mathbf {J}^T}{\partial \theta _4}\mathbf {F},\frac{\partial \mathbf {J}^T}{\partial \theta _5}\mathbf {F},\frac{\partial \mathbf {J}^T}{\partial \theta _6}\mathbf {F}]\) is a complementary term [16], and practically, the contribution of the complementary term to the total robot deformation is very small under normal robot payload [17], thus it can be omitted, i.e.

$$\begin{aligned} \mathbf {K}_x\approx \mathbf {J}^{-T}_F\mathbf {K}_\theta \mathbf {J}^{-1}_x \end{aligned}$$
(7)

Finally, the relationship between \(d\mathbf {x}\) and \(\mathbf {F}\) can be formulated as

$$\begin{aligned} d\mathbf {x}=\mathbf {K}^{-1}_x\mathbf {F}=\mathbf {C}\mathbf {F}=\mathbf {J}_x\mathbf {K}^{-1}_\theta \mathbf {J}^T_F\mathbf {F} \end{aligned}$$
(8)

Equation (8) can be unfolded as

$$\begin{aligned} d\mathbf {x}= \begin{bmatrix} \mathbf {J}_{x11}\sum \limits _{i=1}^n\mathbf {J}_{Fi1}F_i&\cdots&\mathbf {J}_{x16}\sum \limits _{i=1}^n\mathbf {J}_{Fi6}F_i\\ \vdots&\ddots&\vdots \\ \mathbf {J}_{x61}\sum \limits _{i=1}^n\mathbf {J}_{Fi1}F_i&\cdots&\mathbf {J}_{x66}\sum \limits _{i=1}^n\mathbf {J}_{Fi6}F_i\\ \end{bmatrix} \begin{bmatrix} \frac{1}{K_{\theta _1}}\\ \vdots \\ \frac{1}{K_{\theta _6}} \end{bmatrix} =\mathbf {A}\mathbf {k} \end{aligned}$$
(9)

where \(F_i\) is the ith component of \(\mathbf {F}\) and \(\mathbf {J}_{xij}\) or \(\mathbf {J}_{Fij}\) denotes the ith row jth column element of the matrix \(\mathbf {J}_x\) or \(\mathbf {J}_F\), \(i,j=1,\dots ,6\).

To identify the stiffness coefficients \(\mathbf {K}_\theta \) (i.e. \(\mathbf {k}\) in (9)), it usually involves measuring a set of \(\mathbf {F}_i\) and \(d\mathbf {x}_i\) at several robot configurations, \(i=1,\dots ,m\), and constructing the following equation systems:

$$\begin{aligned}{}[d\mathbf {x}_1,\cdots ,d\mathbf {x}_m]^T=[\mathbf {A}_1,\cdots ,\mathbf {A}_m]^T\mathbf {k} \end{aligned}$$
(10)

Equation (10) is simplified as

$$\begin{aligned} \mathbf {y}=\mathbf {M}\mathbf {k} \end{aligned}$$
(11)

Then the stiffness coefficients can be identified by the linear least square method as

$$\begin{aligned} \mathbf {k}=\mathbf {M}^+\mathbf {y} \end{aligned}$$
(12)

The robot used in this paper is a Motoman MH80 industrial robot from Yaskawa, it’s maximal payload is 80 kg and the repeated positioning accuracy is \(\pm 0.07\) mm. The schematic diagram of the robot is shown in Fig. 1, and the D-H parameters are given in Table 1. To identify the stiffness model of the robot via the above-mentioned method, an experiment sytem is etablished and shown in Fig. 2.

Fig. 1.
figure 1

Schematic diagram of Motoman MH80 industrial robot

Table 1. The D-H parameters of the Motoman MH80 industrial robot

In the experiment, 70 robot configurations are randomly generated. At each configuration, the robot is loaded by a spring, and the force applied on the EE is measured by an Omega160 force sensor. The EE frame posture and its deformation are measured by a Leica AT906 Laser tracker via three magnetic holders and a spherically mounted reflector (SMR). The forces and deformations are all transformed to the robot base frame. After the measurements, 50 configurations are randomly chosen for parameter identification, and the remaining 20 configurations are used for verification. The joint stiffness are finally identified and listed in Table 2.

Fig. 2.
figure 2

Experiment setup for stiffness model identification

Fig. 3.
figure 3

Predicted deformations and the actual deformations of the EE

Figure 3 shows the model predicted deformations based on the identified joint stiffness and the actual measured deformations for the 20 verification robot configurations. In this figure, the subscript “a” denotes the actual deformation while the subscript “p” denotes the predicted deformation, dx, dy and dz represent the displacements of the original point of the EE frame while \(\delta _x\), \(\delta _y\) and \(\delta _z\) represent three rotations about x, y and z axis. It can be seen that the deformation predicted via the identified parameters is fairly precise and the modeling error is limited in a narrow band, which verifies the correctness of the parameter identification process.

Table 2. The identified stiffness coefficients (Nm/rad)

4 Feed-Direction Stiffness Index for Robot Machining

Considering that in milling applications, the diameter of the cutter, i.e. lever arm, is relatively small, and the spindle speed is high, the moment exerted by the workpiece on the EE and the corresponding rotation deformation are negligible [18]. Thus Eq. (8) can be unfolded as

$$\begin{aligned} \begin{bmatrix} \varDelta \mathbf {x}\\ \mathbf {0} \end{bmatrix} =\mathbf {C}\mathbf {F}= \begin{bmatrix} \mathbf {C}_{xx}&\mathbf {C}_{xr}\\ \mathbf {C}_{xr}&\mathbf {C}_{rr} \end{bmatrix} \begin{bmatrix} \mathbf {f}\\ \mathbf {0} \end{bmatrix} \end{aligned}$$
(13)

From Eq. (13), it can be easily obtained that

$$\begin{aligned} \varDelta \mathbf {x}=\mathbf {C}_{xx}\mathbf {f} \end{aligned}$$
(14)

where \(\mathbf {f}\) is a \(3\times 1\) vector representing the net force applied on the TCP and \(\varDelta \mathbf {x}\) is the corresponding translational deformation, \(\mathbf {C}_{xx}\) is the upper left \(3\times 3\) submatrix of the compliance matrix \(\mathbf {C}\).

Substituting Eq. (14) into \(\varDelta \mathbf {x}^T\varDelta \mathbf {x}=1\), i.e.

$$\begin{aligned} \mathbf {f}^T\mathbf {C}^T_{xx}\mathbf {C}_{xx}\mathbf {f}=1 \end{aligned}$$
(15)

Equation (15) represents a three dimensional force ellipsoid at a given manipulator configuration, as shown in Fig. 4. The principal axes of the ellipsoid coincide with the eigenvectors of \(\mathbf {C}^T_{xx}\mathbf {C}_{xx}\), and their lengths are equal to the reciprocals of the square roots of the eigenvalues of \(\mathbf {C}^T_{xx}\mathbf {C}_{xx}\). Hence the maximum and minimum forces required to produce a unit deflection are given by \(1/\sqrt{\lambda _{min}}\) and \(1/\sqrt{\lambda _{max}}\), respectively, where \(\lambda _{min}\) and \(\lambda _{max}\) are the minimum and maximum eigenvalues of \(\mathbf {C}^T_{xx}\mathbf {C}_{xx}\). A vector from the center of the force ellipsoid to any point on the surface of the force ellipsoid reflects the stiffness performance of robot machining system along the direction of the vector.

Fig. 4.
figure 4

Three dimensional force ellipsoid

Fig. 5.
figure 5

The force ellipsoid at a CL point

As mentioned before, in order to improve the production efficiency, the stiffness along the cutting feed direction is required high enough to improve the feed rate during the machining process. Figure 5 shows the force ellipsoid at a certain cutter location along a tool path, it is obvious that the length of the axis along the tool feed direction \(\mathbf {r}\) of the ellipsoid H reflects the stiffness of the machining robot along the feed direction. H is determined by the feed direction \(\mathbf {r}\) and the robot configuration \(\mathbf {\uptheta }\), thus H can be used as an optimizing index to eliminate the redundant freedom of the milling robot, which will guarantee a higher production efficiency. Therefore, a redundancy elimination method is proposed as following:

$$\begin{aligned} {\begin{matrix} \max _\gamma \ \ H(\mathbf {\uptheta }(CL,\gamma ),\mathbf {r})\\ s.t. \ \ \mathbf {\uptheta }_{min}\le \mathbf {\uptheta }\le \mathbf {\uptheta }_{max} \end{matrix}} \end{aligned}$$
(16)

where \(\mathbf {\uptheta }_{min}\) and \(\mathbf {\uptheta }_{max}\) are the lower and upper limits of the joint variables. Note that \(\gamma \) is an arbitrary variable, and the nonlinear optimal problem (16) is defined on \(\mathbb {R}\). The problem is numerically solvable by conventional optimization methods, such as the optimization toolbox in MATLAB.

Therefore, the whole post-processing process for the robot milling can be summarized as following: First, the CL data for the specified workpiece is generated by a commercial CAD/CAM software package. Then, five components of the six-dimension vector that describe the posture of the cutting tool are determined. Finally, the last component of the posture vector, i.e. the third Euler angle \(\gamma \), is optimized based on Eq. (16), and the corresponding optimal robot configuration can be calculated by analytical kinematic inverse solution. Through these steps, the redundancy is eliminated and a unique robot trajectory will be generated. The robot trajectory will have the advantage of higher machining efficiency.

5 Experiment

To verify the effectiveness of the proposed method, for simplicity, a face milling tool path is first generated in the NX 8.5 software. Then the tool path is converted to the robot trajectory via Eqs. (3) and (4). To show the influence of the redundant third Euler angle \(\gamma \) on the feed-direction stiffness index, the H values are calculated with different \(\gamma \) values at a CL point and along a tool path. As shown in Fig. 6, the feed-direction stiffness of the robot varies with the redundant Euler angle a lot, the maximal feed-direction stiffness is an order of magnitude higher than the minimal one. As the workpiece is small and the tool path is similar on this occasion, the best and the worst configurations of the robot on the whole tool path vary little, thus three constant third Euler angles in representation of the optimal, the suboptimal and the worst robot configuration are chosen for milling experiment for comparison, i.e. the points labeled as A, B and C in Fig. 6 (a), the corresponding Euler angles are \(\gamma _A=1.531\), \(\gamma _B=1.216\) and \(\gamma _C=-0.2052\) in radian. The robot configuration is determined by the specified redundant Euler angle and the CL point.

Fig. 6.
figure 6

Feed-direction stiffness varies with \(\gamma \) (a) at a CL point and (b) along a tool path

Fig. 7.
figure 7

Robot configurations corresponding to the three specified third Euler angles

The experiment setup is shown in Fig. 7 Conf. A. Within the robot milling system, a SECO milling cutter with a diameter of 10 mm is mounted on a CELL EBS-120g-24000r spindle for cutting. The spindle has a rated power of 7.5 KW and can provide a toque as much as 6 Nm, and it is mounted on the mounting flange of the Motoman MH80 industrial robot. A 6061 aluminum block with a dimension of 260 mm \(\times \) 110 mm\( \times \)80 mm is used as the cutting workpiece and it is fixed on a metallic workbench. The acceleration signal during the milling process is monitored by a PCB 352A25 acceleration sensor attached on the spindle. In the experiment, the robot is first commanded to mill the workpiece under the feed rate of 150 mm/min, 300 mm/min and 600 mm/min with the three previously specified poses as shown in Fig. 7 (Conf. A, Conf. B and Conf. C are corresponding to the three specified Euler angles \(\gamma _A\), \(\gamma _B\) and \(\gamma _C\) ), the acceleration signals are collected and they can help evaluate the machining stability. By analysis of the acceleration signals some conclusions can be obtained. During the whole experiment process, the axial depth of cut is 1.5 mm, the radial depth of cut is 4 mm and the rotational speed of the cutter is 5000 r/min.

Fig. 8.
figure 8

Accelerations with feedrate (a)150 mm/min (b)300 mm/min (c)600 mm/min

Figure 8 shows the acceleration signals during the machining process under different robot configurations and different feed rates. By comparing the acceleration signals under different feed rates and the same robot configuration, it can be found that when the feed rate increases, the acceleration amplitude becomes higher. For example, when machining with Conf. C, the acceleration amplitude is in the range of ±1.5 g under feed rate 150 mm/min, and it becomes ±3 g and ±5 g under feed rate 300 mm/min and 600 mm/min. On the other hand, it can be easily observed that when machining under the same feed rate, the acceleration amplitude decreases progressively when using robot configuration C, B and A. That is to say, a higher feed-direction stiffness can efficiently improve the machining stability, in other words, using the proposed optimization method to generate the robot milling trajectory, a higher feed rate can be chosen and the production efficiency can be improved, which verifies the effectiveness of the proposed optimizing index and the redundancy elimination method.

To further verify the proposed method, three different areas of a plane are machined with the three poses under the feed rate of 300 mm/min, and the machining quality is observed. The machined plane is shown in Fig. 9. It can be easily found that the area machined via the optimized robot configuration A has the best surface quality while the area machined via the worst robot configuration C has the worst surface quality, which is caused by insufficient feed-direction stiffness of the machining robot.

Fig. 9.
figure 9

Areas machined via different robot configurations

6 Conclusion

The post-processing of a milling robot involves converting the 5-axis CL data from a commercial CAD/CAM software to the corresponding 6-axis robot trajectory, which will result in a redundant freedom in the robot system. As the stiffness characteristic of a robot is influenced by the robot configuration, a feed-direction stiffness index is proposed to optimize the redundant freedom after identifying the stiffness model of the robot. Via maximizing the feed-direction stiffness of the robot, the redundant freedom of the robot is eliminated. According to the analysis of the acceleration signals and the machining quality in the experiment, it can be concluded that stronger the stiffness of the robot machining system along feed-direction is, better machining stability and quality is. Thus the post-processing technique for a milling robot proposed in this paper is effective and can enhance the machining performance.