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. General Category - Robot Forum
  4. Robot Geometry, Linear Algebra, Forward and Inverse Kinematics
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

Calculating Forward kinematics connection between theory and practice on example of KUKA robot

  • Askic
  • February 7, 2023 at 1:32 PM
  • Thread is Unresolved
  • Askic
    Reactions Received
    2
    Trophies
    1
    Posts
    25
    • February 13, 2023 at 7:36 AM
    • #21

    Hello MOM,

    I have checked everything again and I'm pretty confident that I didn't make a mistake. The cause of the difference is actual theta offset i.e. what is considered a variable. For example, when setting up coordinate systems, I have considered that zero positions of all angles corresponds to the same configuration that you considered as: [0, -90, 90, 0, 0, 0].

    So when you calculate transformation matrix for [0,-60,90,0,0,0], I need to calculate for [0, +30, 0, 0, 0, 0], because comparing to mine assumed zero configuration, only th2 is changed for +30° because Z axis of joint 2 is oriented "into the screen from us".

    So the following code:

    Code
    % D_H parameters:
    A1d = [0, 30, 0, 0.0, 0.0, 0.0];
    
    th = deg2rad(A1d);
    a1 = 500;   alpha1 = -pi/2;   d1 = 1045;  th1 = th(1);
    a2 = 1300;  alpha2 = 0;       d2 = 0;     th2 = th(2)-pi/2;
    a3 = 55;    alpha3 = -pi/2;   d3 = 0;     th3 = th(3)+pi;
    a4 = 0;     alpha4 = pi/2;    d4 = -1025; th4 = th(4);
    a5 = 0;     alpha5 = -pi/2;   d5 = 0;     th5 = th(5);
    a6 = 0;     alpha6 = pi;      d6 = -290;  th6 = th(6);
    
    T1 = DH_calc(a1,alpha1,d1,th1);
    T2 = DH_calc(a2,alpha2,d2,th2);
    T3 = DH_calc(a3,alpha3,d3,th3);
    T4 = DH_calc(a4,alpha4,d4,th4);
    T5 = DH_calc(a5,alpha5,d5,th5);
    T6 = DH_calc(a6,alpha6,d6,th6);
    
    T06_dh = T1*T2*T3*T4*T5*T6;
    vpa(T06_dh,6)
    Display More

    will produce the following output:

    Code
    [       -0.5, -5.30288e-17,    0.866025,      2261.32]
    [5.30288e-17,          1.0, 9.18485e-17, -1.06281e-13]
    [  -0.866025,  9.18485e-17,        -0.5,       1465.7]
    [          0,            0,           0,          1.0]

    Edited once, last by Askic (February 14, 2023 at 7:25 AM).

  • MOM
    Reactions Received
    175
    Trophies
    7
    Posts
    1,418
    • February 13, 2023 at 9:18 AM
    • #22

    I do not like taking my picture, cut the correct information off and put wrong information on

  • Askic
    Reactions Received
    2
    Trophies
    1
    Posts
    25
    • February 13, 2023 at 9:28 AM
    • #23
    Quote from MOM

    I do not like taking my picture, cut the correct information off and put wrong information on

    I'm afraid this is a misunderstanding, the screenshot I made from your picture is initial configuration with all joint angles assumed to be zero in my calculations. I just attached a picture trying to explain why there is a difference in the calculations mentioned above. So the information is not wrong. The picture corresponds to the DH table I posted together in the same thread.

    Just want to point out once again, that my DH parameters table is derived based on the initial configuration that is shown in the attached picture assuming that theta variables are zero.

    So, when you calculate forward kinematics for [0 -60, 90, 0,0,0], I need to calculate for [0, +30,0,0,0,0].

    I didn't put wrong information, I did put information that correspond to the DH table I placed in the same post.

    I hope it is Ok with you now?

  • MOM
    Reactions Received
    175
    Trophies
    7
    Posts
    1,418
    • February 13, 2023 at 10:02 AM
    • #24

    your and my assumption acually does not count!

    If you have a closer look at the data sheet you will see the zero position of axis 2 and axis 3

    (and this is the correct assumption)

    axis 2:

    +20° | -130°

    axis 3:

    +144° | -100°

    the "|" shows the zero position

  • MOM
    Reactions Received
    175
    Trophies
    7
    Posts
    1,418
    • February 13, 2023 at 9:50 PM
    • #25

    If you think you are right then I can't help you anymore (because I am wrong then).

    But I would request to take my picture from post #21 off!

    From my point of view this thread is closed

  • Askic
    Reactions Received
    2
    Trophies
    1
    Posts
    25
    • February 14, 2023 at 7:27 AM
    • #26

    Ok, thank you very much for your time and help.

    I don't think and don't claim that you're wrong. I just went step by step setting up the DH table according to the DH instructions.

    The difference in calculations was only because of what was considered as variable value in th2 and th3. Because, the way I approached, in the DH tables these values had constant part (offset). For example, var2 = var1+90° is still a variable, but if var1 belongs to a range [-30°, +30°], then var2 will have a different range [60°, 120°] . That is why there was a difference.

    Your posts were very helpful to me.
    We can consider this thread closed.

    Edited once, last by Askic (February 14, 2023 at 7:34 AM).

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