javaKUKA play KUKA in Java

Rotary table

rotary2

1. External axes
What’s the point in installing a rotary table when the robot already has six axes? While the robot arm is indeed agile, adding an external axis could make planning the tool path simpler.

Once the external axes are correctly installed, KRL can directly drive the external axes. For example:
{X 27.3, Y 84.2, Z 20, A 201.5, B 0, C -90, E1 0, E2 -162}
where E1 denotes the linear unit’s displacement; E2 denotes the degree of the rotary table; XYZ specify the tool’s position relative to the BASE; and ABC inform the tool’s orientation (Euler angles) relative to the BASE.

There are many options for using a rotary table:
1. Turn the table using its controller when it is not connected to KUKA.
2. KUKA and the rotary table are fully coupled so the table’s rotation becomes part of the robot’s internal kinematics. A position instruction XYZABC may invoke the table rotation, even if there are no explicit instructions on the external axis.
3. KUKA controls the rotary table but decouples the rotation from the robot’s kinematics (let $EX_KIN={ET1 #NONE, ET1 #NONE,…} in KRC\R1\MADA\$machine.dat). Because the robot is unaware of the effects of the rotation, the offline programming takes care of the cooperation between the robot and rotary table.

The following example takes the third approach. It keeps a hot cutter on one side of the workpiece (a cylinder foam) during the cutting process. The procedure is as follows:
1. Calibrate the tool.
2. Calibrate the rotary table and work piece simultaneously by our 5-point method.
3. The Java program uses the 5-point data to unify the movements of the robot and the rotary table. Finally, the program transforms the tool path into a .src file.
4. Copy the .src file to KUKA and run the machine.

2. Frame
A frame, or a coordinate system, is defined by its position (x, y, z) and its orientation (x, y, and z-axis):
frame rotary
The orientation (three axes) can be written as a 3☓3 matrix (see the methods matrixBy2Axis and matrixBy3Axis in LA class). Combing the position and the orientation leads to a 4☓4 matrix (allowing matrix-matrix multiplication and matrix-vector multiplication):

    $$ \begin{bmatrix} \cdot & \cdot & \cdot & x \\ \cdot & \cdot & \cdot & y \\ \cdot & \cdot & \cdot & z \\ 0 & 0 & 0 & 1\\ \end{bmatrix} $$

where the top left block is the orientation matrix. This matrix and KRL’s XYZABC are interchangeable, see the methods in LA class:
double[][] matrix(double aDeg, double bDeg, double cDeg) //compute a 3*3 matrix from Euler angles
double[][] matrix(double x, double y, double z, double aDeg, double bDeg, double cDeg) //compute a full matrix from XYZABC
double[] ABC(double[][] m) //compute Euler angles from a 3*3 matrix
double[] XYZABC(double[][] m) //compute XYZABC from a full matrix

3. 5-point method
This method computes the BASE ^{0}_{b}T from five points measured on the workpiece. ^{0}_{b}T is the matrix representation of the BASE (frame -1) relative to the WORLD (frame 0), equivalent to the XYZABC model (extended discussions are in entry Kinematics). With a rotary table, the following relationship holds:

    $$ ^{0}_{b}T = {^{0}_{r}T} \;{^{r}_{b}T} $$

where ^{0}_{r}T denotes the frame of rotary table (r) relative to the WORLD while ^{r}_{b}T stands for the BASE (workpiece) relative to the rotary table.
The following image shows the table’s flange and the workpiece can be defined simultaneously by five points:
p: workpiece’s origin;
p_x: a point on the positive x-axis of the workpiece;
p_y: a point on the XY plane (with positive y) of the workpiece;
O_+: the workpiece’s origin when the table is turned 90 degrees;
O_-: workpiece’s origin when the table is turned -90 degrees.
The method does NOT assume the workpiece’s origin is at the center of rotary table nor that the workpiece’s XY plane is parallel to the table’s flange.

rotary4

To measure the five points:
1. Use a pen to mark the origin P of the workpiece (it is the top center of the cylinder in our case), and draw a line on the top as the x-axis.
2. Set the current TOOL/BASE in the pendant (BASE = NULLFRAME, i.e. the WORLD).
3. Manually align the defined tool to a point (e.g., the origin P) on the workpiece, navigate to Display / Actual position to read the position. O+ and O- need to be measured after rotating the table by 90 and -90 degrees, respectively.
4. Put the position data (XYZ) into the Java program. For example:
final double[] P = { 436.39, -1414.71, 763.37 };
final double[] Px = { 341.55, -1315.84, 762.09 };
final double[] Pxy = { 341.52, -1516.66, 764.59 };
final double[] Op = { 425.80, -1412.27, 763.27 }; // +90
final double[] On = { 434.58, -1425.12, 763.49 }; // -90

The Java program Rotary produces a runnable .src file for KUKA, employing the LA (linear algebra) class and the KRLwriter class.

Now, we explain how to transform the 5-point data into the rotating BASE (workpiece). First, the origin, the x-axis, and the y-axis of the table can be defined as O=(O_+ + O_-)/2, P-O, O_+ - O, respectively. Thus, the table’s orientation ^{0}_{r}T (T1 in Java) can be computed in Java by:
O = between(Op, On, 0.5);
T1 = LA.matrixBy2Axis(LA.sub(P, O), LA.sub(Op, O));

where the columns of matrix ^{0}_{r}T represent the x, y, z axis of the orientation of the table:

    $$ ^{0}_{r}T= \begin{bmatrix} x_0 & y_0 & z_0 \\ x_1 & y_1 & z_1 \\ x_2 & y_2 & z_2 \end{bmatrix} $$

Second, the origin, the x-axis, and xy-axis of the BASE (workpiece) are (d,0,0), {^{0}_{r}T}^T(P_x-P), and {^{0}_{r}T}^T(P_{xy}-P), respectively, relative to the rotary table. Thus, ^{r}_{b}T (T2 in Java) can be obtained by:
double[] rela_ax = LA.mul(LA.transpose(T1), LA.sub(Px, P));
double[] rela_ay = LA.mul(LA.transpose(T1), LA.sub(Pxy, P));
double d = LA.dist(O, P);
T2 = LA.matrixBy2Axis(d, 0, 0, rela_ax, rela_ay); // relative to T1;

^{r}_{b}T has a form of

    $$ \begin{bmatrix} \cdot & \cdot & \cdot & d \\ \cdot & \cdot & \cdot & 0 \\ \cdot & \cdot & \cdot & 0 \\ 0 & 0 & 0 & 1\\ \end{bmatrix} $$

where the top left 3☓3 elements represent the frame’s orientation while the last column specifies the frame’s origin.

Third, we compute the BASE ^{0}_{b}T rotated by an arbitrary angle \theta. A 3☓3 matrix represents the rotation around the z-axis and, subsequently, the orientation of the rotated table ^{0}_{b}T' can be obtained:

    $$ ^{0}_{r}T' ={^{0}_{r}T} \begin{bmatrix} \cos\theta & -\sin\theta & 0 \\ \sin\theta & \cos\theta & 0 \\ 0 & 0 &1 \end{bmatrix} \;\;\;\; (1) $$

Combining the origin O leads to a 4☓4 matrix (the top left 3☓3 elements are taken from matrix {^{0}_{r}T'} (1))

    $$ ^{0}_{r}T' \leftarrow \begin{bmatrix} \cdot & \cdot & \cdot & O_x \\ \cdot & \cdot & \cdot & O_y \\ \cdot & \cdot & \cdot & O_z \\ 0 & 0 & 0 & 1\\ \end{bmatrix} \;\;\;\; (2) $$

Therefore, the rotated BASE (relative to WORLD) is

    $$ ^{0}_{b}T = {^{0}_{r}T'} \;{^{r}_{b}T} \;\;\;\; (3) $$

The corresponding Java codes read:
double[][] rotateTable(double angle) {
    double c = Math.cos(angle);
    double s = Math.sin(angle);
    double[] rx = { c, s, 0 };
    double[] ry = { -s, c, 0 };
    double[] nx = LA.mul(T1, rx);
    double[] ny = LA.mul(T1, ry);
    double[][] T1 = LA.matrixBy2Axis(O[0], O[1], O[2], nx, ny);
    return LA.mul(T1, T2);
}

4. Tool path planning
The plan is to cut ten S shapes around a cylinder foam. The first S shape is a parametric curve (parameter s) that lies on the XZ plane of the BASE:

    $$ \begin{bmatrix} x \\ y\\ z \end{bmatrix} = \begin{bmatrix} r\sin(s \frac{7\pi}{4})\\ 50-R \\ H_0+sH\\ \end{bmatrix} $$

Other S shapes are the rotated (around the z-axis of the BASE) copies of the original:

    $$ \begin{bmatrix} x' \\ y'\\ z' \end{bmatrix} = \begin{bmatrix} \cos(-\theta) & -\sin(-\theta) & 0 \\ \sin(-\theta) & \cos(-\theta) & 0 \\ 0 & 0 & 1\\ \end{bmatrix} \begin{bmatrix} x \\ y\\ z \end{bmatrix} \;\;\;\;(4) $$

If there is no rotary table, the robot has to turn the tool around the cylinder. In this situation, it is difficult to avoid a collision between the robot and the workpiece. With the help of a rotary table, the robot arm can stay on one side of the workpiece with the following process:
1. Cut the first S shape.
2. Rotate the table by \theta, update BASE by (3) and
cut the S shape, which is rotated -\theta from the first one.
3. Rotate the table by 2\theta, update BASE by (3) and
cut the S shape, which is rotated -2\theta from the first one.

The signs of \theta in (1) and (4) are opposite, meaning the BASE’s rotations “compensate” the rotations of the S shapes.

rotary7

The corresponding KRL codes look like:
$BASE={X 437.3,Y -1416.8,Z 763.4,A 115.8,B 0.6,C 0.2}
PTP {X 27.3,Y -84.2,Z 20,A 57.5,B 0,C -90,E1 0,E2 0}
SPLINE
SPL {X 27.3,Y -84.2,Z 20,A 57.5,B 0,C -90,E1 0,E2 0}

$BASE={X 434.9,Y -1413,Z 763.3,A 151.8,B 0.4,C 0.7}
PTP {X -27.3,Y -84.2,Z 20,A 21.5,B 0,C -90,E1 0,E2 36}
SPLINE
SPL {X -27.3,Y -84.2,Z 20,A 21.5,B 0,C -90,E1 0,E2 36}

$BASE={X 430.6,Y -1411.3,Z 763.3,A -172.2,B 0,C 1}
PTP {X -71.6,Y -52,Z 20,A -14.5,B 0,C -90,E1 0,E2 72}
SPLINE
SPL {X -71.6,Y -52,Z 20,A -14.5,B 0,C -90,E1 0,E2 72}

Kuka is blind on workpiece’ rotation; however, the updates of $BASE guarantee the relative position between the robot and the workpiece is correct.

Each S shape corresponds to a SPLINE of three segments (SPLs, SLIN, SPLs):
SPLINE
SPL {X 27.3,Y 84.2,Z 20,A 201.5,B 0,C -90,E1 0,E2 -162} //downward cut
SPL {X -0.8,Y 93.3,Z 0}

SPL {X 100.7,Y 60.4,Z -380}

SLIN {X 100.7,Y 60.4,Z -380,A 266.5,B 0,C -90} //change orientation

SPL {X 100.7,Y 60.4,Z -380}//upward cut
SPL {X 117.8,Y 54.8,Z -360}

SPL {X 27.3,Y 84.2,Z 20}
ENDSPLINE

The following image shows that the two cuts follow the same path but with different orientations.

rotary6

This example indicates the added freedom given by a rotary table can facilitate path planning, especially when collision and the robot’s workspace are critical. The 5-point method is for general purpose; it computes the BASE rotated with the rotary table.

5. 5-point method revisited
When the workpieces’s origin is close to the turntable’s center, the aforementioned 5-point method may result in inaccurate calibration. To solve this problem, one can measure the 5 points as in the following image

Screen Shot 2020-07-11 at 5.33.57 PM

The measured coordinates are saved in the Java codes, for example:
final double[] P = -558.92, 1400.13, 841.81 ;
final double[] Px = -77.44, 1270.00, 843.67 ;
final double[] Pxy = -440.21, 1840.17, 840.69;
final double[] Pxy90p = -999.72, 1516.83, 842.63; // point xy +90
final double[] Pxy90n = -116.46, 1281.05, 844.92 ; // point xy -90

The origin, the x-axis, and the y-axis of the table can be defined as O=(O_+ + O_-)/2,  O_- -O,  P_{xy} - O respectively. Thus, the table’s orientation ^{0}_{r}T (T1 in Java) can be computed in Java by
O = M.between(0.5, Pxy90p, Pxy90n);
T1 = LA.matrixby2Axis(LA.sub(Pxy90n, O), LA.sub(Pxy, O));

where the columns of matrix ^{0}_{r}T represent the x, y, z axis of the orientation of the table:

    $$ ^{0}_{r}T= \begin{bmatrix} x_0 & y_0 & z_0 \\ x_1 & y_1 & z_1 \\ x_2 & y_2 & z_2 \end{bmatrix} $$

Second, the origin, the x-axis, and xy-axis of the BASE (workpiece) are {^{0}_{r}T}^T(P-O), {^{0}_{r}T}^T(P_x-O), and {^{0}_{r}T}^T(P_{xy}-O), respectively, relative to the rotary table. Thus, ^{r}_{b}T (T2 in Java) can be obtained by:
double[] rela ax = LA.mul(T1T, LA.sub(Px, P));

double[] rela ay = LA.mul(T1T, LA.sub(Pxy, P));
double[] d = LA.mul(T1T, LA.sub(P, O));
T2 = LA.matrixby2Axis(d[0], d[1], d[2], rela ax, rela ay);

References:
1) Kuka manual, on the calibration of the base and the external kinematic system.
2) J. J. Graig, Introduction to Robotics, chapter 2.
3) P. Schneider and D. Eberly, Geometric Tools for Computer Graphics, chapters 2,3,4.

Comments are closed.