1. Home
    1. Dashboard
    2. Search
  2. Forum
    1. Unresolved Threads
    2. Members
      1. Recent Activities
      2. Users Online
      3. Team Members
      4. Search Members
      5. Trophys
  3. Articles
  4. Blog
  5. Videos
  6. Jobs
  7. Shop
    1. Orders
  • Login or register
  • Search
This Thread
  • Everywhere
  • This Thread
  • This Forum
  • Articles
  • Pages
  • Forum
  • Blog Articles
  • Products
  • More Options
  1. Robotforum - Support and discussion community for industrial robots and cobots
  2. Forum
  3. Industrial Robot Support and Discussion Center
  4. KUKA Robot Forum
Your browser does not support videos RoboDK Software for simulation and programming
Visit our Mainsponsor
IRBCAM
Robotics Channel
Robotics Training
Advertise in robotics
Sponsored Ads

Going from KUKA Euler angles to transformation matrix.

  • abrady
  • December 15, 2015 at 7:28 PM
  • Thread is Resolved
  • abrady
    Trophies
    4
    Posts
    16
    • December 15, 2015 at 7:28 PM
    • #1

    Hi.

    I've recently run a series of tests on a KR-60 Robot using a KRC2 controller.

    I have position data at the tool center point, in the tool frame and I'm interested in getting position data from a DIFFERENT point on the tool for which I have the coordinates in the tool frame.

    I've created a 4x4 transformation matrix that represents the motion of the tool during the test, and I will multiply the vector of the point I'm interested in by that matrix to get its final position.

    The only thing I'm a bit confused about is the KUKA representation of Euler angles, and I'd like to make sure I'm doing the right thing since we will be publishing this data in a scientific journal.

    I'm under the impression that the angles are represented as INTRINSIC X''Y'Z Euler angles starting with Z (A), then Y (B), then X (C)

    So, to construct a rotation matrix from thos angles I need the matrix
    R=X''Y'Z which would be equivalent to R=ZYX where

    X=[1 0 0
    0 cos(C) -sin(C)
    0 sin(C) cos(C)]

    Y=[cos(B) 0 sin(B)
    0 1 0
    sin(B) 0 cos(B)]

    Z=[cos(A) -sin(A) 0
    sin(A) cos(A) 0
    0 0 1]

    Is this the correct way to compute a rotation matrix from the KUKA euler angles A,B,C?

    Thanks for your help.

  • panic mode
    Reactions Received
    1,280
    Trophies
    11
    Posts
    13,083
    • December 15, 2015 at 8:22 PM
    • #2

    you have mistake for rotation matrix Ry(B). There sin(B) in lower left corner should be negative.
    Once you multiply those three 3x3 elementary rotation matrices, you will get single 3x3 matrix R=Rz(A)*Ry(B)*Rx(C)

    https://en.wikipedia.org/wiki/Rotation_matrix

    1) read pinned topic: READ FIRST...

    2) if you have an issue with robot, post question in the correct forum section... do NOT contact me directly

    3) read 1 and 2

  • Spl
    Reactions Received
    5
    Trophies
    3
    Posts
    178
    • December 16, 2015 at 6:24 AM
    • #3

    Here's euler angle formulas for all rotation combinations.

    http://www.geometrictools.com/Documentation/EulerAngles.pdf

  • whitegreen
    Trophies
    4
    Posts
    31
    • December 16, 2015 at 7:00 AM
    • #4

    I wrote a set of Linear algebra routines for KUKA.
    Computing a matrix from ABC Euler angles:
    public static double[][] matrix(double aDeg, double bDeg, double cDeg) {
    //ABC: Euler angles, A: round z-axis B: round y-axis C: round y-axis
    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[][] tt = new double[3][];
    tt[0] = new double[] { ca * cb, sa * cc + ca * sb * sc, sa * sc - ca * sb * cc };
    tt[1] = new double[] { -sa * cb, ca * cc - sa * sb * sc, ca * sc + sa * sb * cc};
    tt[2] = new double[] { sb, -cb * sc, cb * cc };
    return tt;
    }

    applying the matrix: a is the rotation marix, b is the vector
    public static double[] mul(double[][] a, double[] b) {
    double[] re = new double[3];
    int len = a[0].length;
    if (len == 4) { // matrix a[][] includes both rotation and the position of the current frame
    for (int i = 0; i < 3; i++)
    re[i] = a[i][0] * b[0] + a[i][1] * b[1] + a[i][2] * b[2] + a[i][3];
    }
    else if (len == 3) { // only rotation
    for (int i = 0; i < 3; i++)
    re[i] = a[i][0] * b[0] + a[i][1] * b[1] + a[i][2] * b[2];
    }
    return re;
    }

    Very often, one computes the matrix from both Euler angles (ABC) and the position (XYZ) of the current frame as:
    public static double[][] matrix(double x, double y, double z, 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[][] tt = new double[3][];
    tt[0] = new double[] { ca * cb, sa * cc + ca * sb * sc, sa * sc - ca * sb * cc, x };
    tt[1] = new double[] { -sa * cb, ca * cc - sa * sb * sc, ca * sc + sa * sb * cc, y };
    tt[2] = new double[] { sb, -cb * sc, cb * cc, z };
    return tt;
    }
    Hope it’s helpful.

    Edited once, last by whitegreen (December 16, 2015 at 7:09 AM).

  • Fubini
    Reactions Received
    278
    Trophies
    9
    Posts
    1,888
    • December 16, 2015 at 10:07 AM
    • #5

    Or if you want to do it online: Take a look at methods RPY_TO_MAT/MAT_TO_RPY found inside kue_weg.src in folder C:/KRC/UTIL on any KRC installation.

    Fubini

  • abrady
    Trophies
    4
    Posts
    16
    • December 18, 2015 at 6:36 PM
    • #6

    Great, thanks for the clarification everyone.

    Panic mode: Good catch, and thanks for confirming that I am multiplying the matrices in the correct order.

    Fubini, for future tests I'll definitely have a look at that. For now it's too late since we already have all the data but that's a great tip, I can use it to check my own matrix calculation vs the built-in one.

Advertising from our partners

IRBCAM
Robotics Channel
Robotics Training
Advertise in robotics
Advertise in Robotics
Advertise in Robotics

Job Postings

  • Anyware Robotics is hiring!

    yzhou377 February 23, 2025 at 4:54 AM
  • How to see your Job Posting (search or recruit) here in Robot-Forum.com

    Werner Hampel November 18, 2021 at 3:44 PM
Your browser does not support videos RoboDK Software for simulation and programming

Tag Cloud

  • abb
  • Backup
  • calibration
  • Communication
  • CRX
  • DCS
  • dx100
  • dx200
  • error
  • Ethernet
  • Ethernet IP
  • external axis
  • Fanuc
  • help
  • hmi
  • I/O
  • irc5
  • IRVIsion
  • karel
  • kawasaki
  • KRC2
  • KRC4
  • KRC 4
  • KRL
  • KUKA
  • motoman
  • Offset
  • PLC
  • PROFINET
  • Program
  • Programming
  • RAPID
  • robodk
  • roboguide
  • robot
  • robotstudio
  • RSI
  • safety
  • Siemens
  • simulation
  • SPEED
  • staubli
  • tcp
  • TCP/IP
  • teach pendant
  • vision
  • Welding
  • workvisual
  • yaskawa
  • YRC1000

Thread Tag Cloud

  • abb
  • Backup
  • calibration
  • Communication
  • CRX
  • DCS
  • dx100
  • dx200
  • error
  • Ethernet
  • Ethernet IP
  • external axis
  • Fanuc
  • help
  • hmi
  • I/O
  • irc5
  • IRVIsion
  • karel
  • kawasaki
  • KRC2
  • KRC4
  • KRC 4
  • KRL
  • KUKA
  • motoman
  • Offset
  • PLC
  • PROFINET
  • Program
  • Programming
  • RAPID
  • robodk
  • roboguide
  • robot
  • robotstudio
  • RSI
  • safety
  • Siemens
  • simulation
  • SPEED
  • staubli
  • tcp
  • TCP/IP
  • teach pendant
  • vision
  • Welding
  • workvisual
  • yaskawa
  • YRC1000
  1. Privacy Policy
  2. Legal Notice
Powered by WoltLab Suite™
As a registered Member:
* You will see no Google advertising
* You can translate posts into your local language
* You can ask questions or help the community with your knowledge
* You can thank the authors for their help
* You can receive notifications of replies or new topics on request
* We do not sell your data - we promise

JOIN OUR GREAT ROBOTICS COMMUNITY.
Don’t have an account yet? Register yourself now and be a part of our community!
Register Yourself Lost Password
Robotforum - Support and discussion community for industrial robots and cobots in the WSC-Connect App on Google Play
Robotforum - Support and discussion community for industrial robots and cobots in the WSC-Connect App on the App Store
Download