1. Hello, ABC!
Euler angles A, B, and C are essential in KUKA KRL language. This introduction explains and compares three models of orientation: fixed angles, Euler angles (ABC), and the 3-point method.
A typical KRL file starts with
$TOOL=TOOL_DATA[1]
$BASE=BASE_DATA[1]
PTP XHOME
PTP {X 280, Y 0, Z -10, A 30, B 90, C 0}
…
The first two lines specify the TOOL Frame (relative to the FLANGE frame) and the BASE frame (relative to the WORLD frame), after you define them with the teach pendant. The following scripts specify the positions (X, Y, Z) and the orientations (A, B, C) of the tool in the BASE frame.
For instance, {X 0, Y 0, Z 0, A 0, B 0, C 0} means that the tool is aligned with the BASE Frame:
Through this post, TOOL refers to the static (unless one explicitly changes it in KRL codes) frame of the tool relative to the FLANGE. Conversely, “tool” refers to the variable position of the tool in the BASE.
Tips:
To see the TOOL data, navigate in the pendant to Start-up / Calibrate / Tool / Numeric input.
To see the BASE data navigate to Start-up / Calibrate / BASE / Numeric input.
To see the tool’s current position, first set the current TOOL/BASE in the pendant, and then go to Display / Actual position.
2. X-Y-Z fixed angles
As Kuka uses ABC representation (Euler angles) instead of fixed angles, this section can be skipped. Nevertheless, understanding fixed angles is critical to grasping the spirit of Euler angles. They are simply two interpretations of one mathematical object!
It is a convention to represent the rotation in a 2D space with a 2 by 2 matrix:
One can obtain the coordinates of a point after rotation by
Extending this formulism into 3D, we get three matrices for rotations about the x, y, and z-axis respectively (here, we replace cos with c and sin with s):
Therefore, rotating a point (x, y, z) first by the x-axis, then by the y-axis, and finally by the z-axis leads to
where the x, y, and z axes are fixed (not affected by rotation). That is why people term such representations with X-Y-Z fixed angles.
3. Z-Y-X Euler angles
In KRL language, the following transformation {X 0, Y 0, Z 0, A 90, B -90, C -90} can be virtually performed by:
Frist, rotating the tool about the tool’s z-axis through an angle A (90 degree)
Second, rotating the tool about the tool’s y-axis through an angle B (-90 degree)
Third, rotating the tool about the tool’s x-axis through an angle C (-90 degree)
The process is illustrated below:
The intermediate steps are only for illustrative purposes, as the robot does NOT follow these steps to reach the final position. Therefore, the unreachable intermediate state {A 90, B -90, C 0} (third column in the figure) does not prevent the machine from arriving its final destination.
Contrary to fixed angles (1), the matrix for a successive rotation is at the right side of the multiplication in the ABC representation (Euler angles). For instance, rotating about the tool’s z-axis (A) and then about its y-axis (B) amounts to
The general formula for Euler angle rotations is given by
It is surprising that formulas (1) and (2) are identical. This suggests that X-Y-Z fixed angles is the same as Z-Y-X Euler angles!
Our LA (linear algebra) class implements the conversion between ABC and the rotation matrix by the two functions:
double[][] matrix(double aDeg, double bDeg, double cDeg) {
double a = -aDeg * PI / 180;
double b = -bDeg * PI / 180;
double c = -cDeg * PI / 180;
double ca = Math.cos(a);
double sa = Math.sin(a);
double cb = Math.cos(b);
double sb = Math.sin(b);
double cc = Math.cos(c);
double sc = Math.sin(c);
double[][] m = new double[3][];
m[0] = new double[] { ca * cb, sa * cc + ca * sb * sc, sa * sc – ca * sb * cc };
m[1] = new double[] { -sa * cb, ca * cc – sa * sb * sc, ca * sc + sa * sb * cc};
m[2] = new double[] { sb, -cb * sc, cb * cc };
return tt;
}
double[] ABC(double[][] m) {
double sb = m[2][0];
double cb = Math.sqrt(1 – sb * sb); // + –
double ca = m[0][0];
double sa = -m[1][0];
double cc = m[2][2];
double sc = -m[2][1];
double a = Math.atan2(sa, ca) * -180 /PI;
double b = Math.atan2(sb, cb) * -180 / PI;
double c = Math.atan2(sc, cc) * -180 / PI;
return new double[] { a, b, c };
}
VisualABC1 (dependencies: LA, Processing, and PeasyCam) visualizes the tool in the BASE frame.
4. 3-point method
Given the vectors of the tool’s three axes (normalized):
a straightforward representation of orientation is a 3 by 3 orthogonal matrix (whose columns are orthonormal vectors):
We can also incorporate the tool’s position (XYZ)
into the matrix to obtain the following general formula:
Comparing (3) with (2) and (4), we can determine the correspondences between the 3-point method and the ABC model. The LA class offers a method of coverting an orientation matrix to ABC:
double[] ABC(double[][] m) { // Euler angles from 3*3 matrix
double sb = m[2][0];
double cb = Math.sqrt(1 – sb * sb); // + –
double ca = m[0][0];
double sa = -m[1][0];
double cc = m[2][2];
double sc = -m[2][1];
double a = Math.atan2(sa, ca) * -180 /PI;
double b = Math.atan2(sb, cb) * -180 / PI;
double c = Math.atan2(sc, cc) * -180 / PI;
return new double[] { a, b, c };
}
Formula (3) complies with Kuka’s “3-point” method:
1) define the origin o;
2) find a point p on the positive x-axis;
3) find a point q in the XY plane with a positive Y value.
The y-axis can be found by , where . The z-axis can be obtained by cross product of x and y (both normalized): . Therefore, the 3-point method is equivalent to specifying the vectors of x, y, z-axis.
The LA class also contains a method static double[][] matrixBy2Axis(double[] _dx, double[] _dxy) which returns the orientation matrix by 3-point method.
5. XYZ & ABC
In linear algebra a point (x, y, z) is often represented by a column vector as in formulas (1) (2) (3). Translating a point is equivalent to vector addition
An alternative is multiplying a 3 by 4 matrix with the column vector:
Now, we can integrate the rotation and the translation into one formula:
which is consistent with (2) and (3).
One can perform transformations with the LA class, for example (VisualXYZABC):
double[][] matrix = LA.matrix(20, 30, 40, -90, -90);
double[] point={50, 0, 0};
double[] point_transformed = LA.mul(matrix, point);
6. TOOL & BASE revisited
Under most circumstances, a Kuka user first defines the TOOL and the BASE with the pendant and then refers to them in KRL codes However, one can always define a TOOL directly in KRL as
$TOOL={X 280, Y 0, Z -10, A 30, B 90, C 0}
where the XYZABC data are relative to the FLANGE. Likewise we may directly write
$BASE={X 0, Y 0, Z -200, A 90, B 0, C 0}
where the XYZABC data are relative to the WORLD.
The contingence of tool and base coordinates makes the serial manipulator unique among CNC machines. We will use this feature in another entry to facilitate turntable use.
References:
1) Kuka manual, on tool calibration and base calibration.
2) J. J. Graig, Introduction to Robotics, chapter 2.
3) P. Schneider and D. Eberly, Geometric Tools for Computer Graphics, chapters 2,3,4.