DH Parameters for calculations of kinematics and dynamics
Denavit Hartenberg Parameters - DH Parameters
Denavit–Hartenberg parameters are used to calculate kinematics and dynamics of UR robots.
The definition of the Denavit–Hartenberg parameters can be found here: http://en.wikipedia.org/wiki/Denavit%E2%80%93Hartenberg_parameters
Animation to explain the Denavit–Hartenberg parameters: https://www.youtube.com/watch?v=rA9tm0gTln8
Note: UR “a” parameter = Wikipedia “r” parameter.
The Denavit–Hartenberg parameters in UR robots are described as the below diagrams.
The Denavit–Hartenberg parameters of UR robots are shown as below.
For UR20 see following link: https://www.universal-robots.com/download/mechanical-ur20/dh-parameters-for-calculations-of-kinematics-and-dynamics-ur20/
UR3e | |||||||
Kinematics | theta [rad] | a [m] | d [m] | alpha [rad] | Dynamics | Mass [kg] | Center of Mass [m] |
Joint 1 | 0 | 0 | 0.15185 | π/2 | Link 1 | 1.98 | [0, -0.02, 0] |
Joint 2 | 0 | -0.24355 | 0 | 0 | Link 2 | 3.4445 | [0.13, 0, 0.1157] |
Joint 3 | 0 | -0.2132 | 0 | 0 | Link 3 | 1.437 | [0.05, 0, 0.0238] |
Joint 4 | 0 | 0 | 0.13105 | π/2 | Link 4 | 0.871 | [0, 0, 0.01] |
Joint 5 | 0 | 0 | 0.08535 | -π/2 | Link 5 | 0.805 | [0, 0, 0.01] |
Joint 6 | 0 | 0 | 0.0921 | 0 | Link 6 | 0.261 | [0, 0, -0.02] |
UR5e | |||||||
Kinematics | theta [rad] | a [m] | d [m] | alpha [rad] | Dynamics | Mass [kg] | Center of Mass [m] |
Joint 1 | 0 | 0 | 0.1625 | π/2 | Link 1 | 3.761 | [0, -0.02561, 0.00193] |
Joint 2 | 0 | -0.425 | 0 | 0 | Link 2 | 8.058 | [0.2125, 0, 0.11336] |
Joint 3 | 0 | -0.3922 | 0 | 0 | Link 3 | 2.846 | [0.15, 0.0, 0.0265] |
Joint 4 | 0 | 0 | 0.1333 | π/2 | Link 4 | 1.37 | [0, -0.0018, 0.01634] |
Joint 5 | 0 | 0 | 0.0997 | -π/2 | Link 5 | 1.3 | [0, 0.0018,0.01634] |
Joint 6 | 0 | 0 | 0.0996 | 0 | Link 6 | 0.365 | [0, 0, -0.001159] |
UR10e | |||||||
Kinematics | theta [rad] | a [m] | d [m] | alpha [rad] | Dynamics | Mass [kg] | Center of Mass [m] |
Joint 1 | 0 | 0 | 0.1807 | π/2 | Link 1 | 7.369 | [0.021, 0.000, 0.027] |
Joint 2 | 0 | -0.6127 | 0 | 0 | Link 2 | 13.051 | [0.38, 0.000, 0.158] |
Joint 3 | 0 | -0.57155 | 0 | 0 | Link 3 | 3.989 | [0.24, 0.000, 0.068] |
Joint 4 | 0 | 0 | 0.17415 | π/2 | Link 4 | 2.1 | [0.000, 0.007, 0.018] |
Joint 5 | 0 | 0 | 0.11985 | -π/2 | Link 5 | 1.98 | [0.000, 0.007, 0.018] |
Joint 6 | 0 | 0 | 0.11655 | 0 | Link 6 | 0.615 | [0, 0, -0.026] |
UR16e | |||||||
Kinematics | theta [rad] | a [m] | d [m] | alpha [rad] | Dynamics | Mass [kg] | Center of Mass [m] |
Joint 1 | 0 | 0 | 0.1807 | π/2 | Link 1 | 7.369 | [0.000, -0.016, 0.030] |
Joint 2 | 0 | -0.4784 | 0 | 0 | Link 2 | 10.450 | [0.302, 0.000, 0.160] |
Joint 3 | 0 | -0.36 | 0 | 0 | Link 3 | 4.321 | [0.194, 0.000, 0.065] |
Joint 4 | 0 | 0 | 0.17415 | π/2 | Link 4 | 2.180 | [0.000, -0.009, 0.011] |
Joint 5 | 0 | 0 | 0.11985 | -π/2 | Link 5 | 2.033 | [0.000, 0.018, 0.012] |
Joint 6 | 0 | 0 | 0.11655 | 0 | Link 6 | 0.907 | [0, 0, -0.044] |
UR3 | |||||||
Kinematics | theta [rad] | a [m] | d [m] | alpha [rad] | Dynamics | Mass [kg] | Center of Mass [m] |
Joint 1 | 0 | 0 | 0.1519 | π/2 | Link 1 | 2 | [0, -0.02, 0] |
Joint 2 | 0 | -0.24365 | 0 | 0 | Link 2 | 3.42 | [0.13, 0, 0.1157] |
Joint 3 | 0 | -0.21325 | 0 | 0 | Link 3 | 1.26 | [0.05, 0, 0.0238] |
Joint 4 | 0 | 0 | 0.11235 | π/2 | Link 4 | 0.8 | [0, 0, 0.01] |
Joint 5 | 0 | 0 | 0.08535 | -π/2 | Link 5 | 0.8 | [0, 0, 0.01] |
Joint 6 | 0 | 0 | 0.0819 | 0 | Link 6 | 0.35 | [0, 0, -0.02] |
UR5 | |||||||
Kinematics | theta [rad] | a [m] | d [m] | alpha [rad] | Dynamics | Mass [kg] | Center of Mass [m] |
Joint 1 | 0 | 0 | 0.089159 | π/2 | Link 1 | 3.7 | [0, -0.02561, 0.00193] |
Joint 2 | 0 | -0.425 | 0 | 0 | Link 2 | 8.393 | [0.2125, 0, 0.11336] |
Joint 3 | 0 | -0.39225 | 0 | 0 | Link 3 | 2.33 | [0.15, 0.0, 0.0265] |
Joint 4 | 0 | 0 | 0.10915 | π/2 | Link 4 | 1.219 | [0, -0.0018, 0.01634] |
Joint 5 | 0 | 0 | 0.09465 | -π/2 | Link 5 | 1.219 | [0, 0.0018,0.01634] |
Joint 6 | 0 | 0 | 0.0823 | 0 | Link 6 | 0.1879 | [0, 0, -0.001159] |
UR10 | |||||||
Kinematics | theta [rad] | a [m] | d [m] | alpha [rad] | Dynamics | Mass [kg] | Center of Mass [m] |
Joint 1 | 0 | 0 | 0.1273 | π/2 | Link 1 | 7.1 | [0.021, 0.000, 0.027] |
Joint 2 | 0 | -0.612 | 0 | 0 | Link 2 | 12.7 | [0.38, 0.000, 0.158] |
Joint 3 | 0 | -0.5723 | 0 | 0 | Link 3 | 4.27 | [0.24, 0.000, 0.068] |
Joint 4 | 0 | 0 | 0.163941 | π/2 | Link 4 | 2 | [0.000, 0.007, 0.018] |
Joint 5 | 0 | 0 | 0.1157 | -π/2 | Link 5 | 2 | [0.000, 0.007, 0.018] |
Joint 6 | 0 | 0 | 0.0922 | 0 | Link 6 | 0.365 | [0, 0, -0.026] |
Download the excel file below for an overview and understanding how the transformation is done in regards to the position of the robot's joints.