Coding Denavit-Hartenberg Tables Using Python

Now that we’ve seen how to fill in Denavit-Hartenberg Tables, let’s see how we can use these tables and Python code to calculate homogeneous transformation matrices for robotic arms. Our goal is to then use these homogeneous transformation matrices to determine the position and orientation of the end effector of a robotic arm.

Example 1 – Cartesian Robot

15-example-of-cartesian-robot
13-cartesian-robotJPG

Let’s start by calculating the homogeneous transformation matrix from frame 0 to frame 1.

Here was our derivation of the Denavit-Hartenberg table for the cartesian robot. Let’s enter that one in code. Here is the program in Python:

import numpy as np # Scientific computing library

# Project: Coding Denavit-Hartenberg Tables Using Python - Cartesian Robot
#          This only looks at frame 0 to frame 1.
# Author: Addison Sears-Collins
# Date created: August 21, 2020

# Link lengths in centimeters
a1 = 1 # Length of link 1
a2 = 1 # Length of link 2
a3 = 1 # Length of link 3

# Initialize values for the displacements
d1 = 1 # Displacement of link 1
d2 = 1 # Displacement of link 2
d3 = 1 # Displacement of link 3

# Declare the Denavit-Hartenberg table. 
# It will have four columns, to represent:
# theta, alpha, r, and d
# We have the convert angles to radians.
d_h_table = np.array([[np.deg2rad(90), np.deg2rad(90), 0, a1 + d1],
                      [np.deg2rad(90), np.deg2rad(-90), 0, a2 + d2],
                      [0, 0, 0, a3 + d3]]) 

# Create the homogeneous transformation matrix
homgen_0_1 = np.array([[np.cos(d_h_table[0,0]), -np.sin(d_h_table[0,0]) * np.cos(d_h_table[0,1]), np.sin(d_h_table[0,0]) * np.sin(d_h_table[0,1]), d_h_table[0,2] * np.cos(d_h_table[0,0])],
                      [np.sin(d_h_table[0,0]), np.cos(d_h_table[0,0]) * np.cos(d_h_table[0,1]), -np.cos(d_h_table[0,0]) * np.sin(d_h_table[0,1]), d_h_table[0,2] * np.sin(d_h_table[0,0])],
                      [0, np.sin(d_h_table[0,1]), np.cos(d_h_table[0,1]), d_h_table[0,3]],
                      [0, 0, 0, 1]])  

# Print the homogeneous transformation matrix from frame 1 to frame 0.
print(homgen_0_1)

Run the program.

Here is the output:

1-output-cartesian-robotJPG

The output is saying that the rotation matrix from frame 0 to frame 1 is as follows:

16-third-columnJPG

This is exactly what I got on an earlier post where I derived the rotation matrix from frame 0 to frame 1 for a cartesian robot.

You can also see the displacement vector from frame 1 to frame 0, the 3×1 vector on the right side of the matrix. The vector makes sense because it is saying that the position of frame 1 relative to frame 0 in the z0 direction is 2 units (because a1 = 1 and d1 = 1):

2-2-unitsJPG

Now, let’s add the two other homogeneous transformation matrices: from frame 1 to 2 and from frame 2 to 3.

13-cartesian-robotJPG

Here is the code:

import numpy as np # Scientific computing library

# Project: Coding Denavit-Hartenberg Tables Using Python - Cartesian Robot
# Author: Addison Sears-Collins
# Date created: August 21, 2020

# Link lengths in centimeters
a1 = 1 # Length of link 1
a2 = 1 # Length of link 2
a3 = 1 # Length of link 3

# Initialize values for the displacements
d1 = 1 # Displacement of link 1
d2 = 1 # Displacement of link 2
d3 = 1 # Displacement of link 3

# Declare the Denavit-Hartenberg table. 
# It will have four columns, to represent:
# theta, alpha, r, and d
# We have the convert angles to radians.
d_h_table = np.array([[np.deg2rad(90), np.deg2rad(90), 0, a1 + d1],
                      [np.deg2rad(90), np.deg2rad(-90), 0, a2 + d2],
                      [0, 0, 0, a3 + d3]]) 

# Homogeneous transformation matrix from frame 0 to frame 1
i = 0
homgen_0_1 = np.array([[np.cos(d_h_table[i,0]), -np.sin(d_h_table[i,0]) * np.cos(d_h_table[i,1]), np.sin(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.cos(d_h_table[i,0])],
                      [np.sin(d_h_table[i,0]), np.cos(d_h_table[i,0]) * np.cos(d_h_table[i,1]), -np.cos(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.sin(d_h_table[i,0])],
                      [0, np.sin(d_h_table[i,1]), np.cos(d_h_table[i,1]), d_h_table[i,3]],
                      [0, 0, 0, 1]])  

# Homogeneous transformation matrix from frame 1 to frame 2
i = 1
homgen_1_2 = np.array([[np.cos(d_h_table[i,0]), -np.sin(d_h_table[i,0]) * np.cos(d_h_table[i,1]), np.sin(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.cos(d_h_table[i,0])],
                      [np.sin(d_h_table[i,0]), np.cos(d_h_table[i,0]) * np.cos(d_h_table[i,1]), -np.cos(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.sin(d_h_table[i,0])],
                      [0, np.sin(d_h_table[i,1]), np.cos(d_h_table[i,1]), d_h_table[i,3]],
                      [0, 0, 0, 1]])  

# Homogeneous transformation matrix from frame 2 to frame 3
i = 2
homgen_2_3 = np.array([[np.cos(d_h_table[i,0]), -np.sin(d_h_table[i,0]) * np.cos(d_h_table[i,1]), np.sin(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.cos(d_h_table[i,0])],
                      [np.sin(d_h_table[i,0]), np.cos(d_h_table[i,0]) * np.cos(d_h_table[i,1]), -np.cos(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.sin(d_h_table[i,0])],
                      [0, np.sin(d_h_table[i,1]), np.cos(d_h_table[i,1]), d_h_table[i,3]],
                      [0, 0, 0, 1]])  

homgen_0_3 = homgen_0_1 @ homgen_1_2 @ homgen_2_3

# Print the homogeneous transformation matrices
print("Homogeneous Matrix Frame 0 to Frame 1:")
print(homgen_0_1)
print()
print("Homogeneous Matrix Frame 1 to Frame 2:")
print(homgen_1_2)
print()
print("Homogeneous Matrix Frame 2 to Frame 3:")
print(homgen_2_3)
print()
print("Homogeneous Matrix Frame 0 to Frame 3:")
print(homgen_0_3)
print()

Now, run the code.

Here is the output:

3-here-is-the-outputJPG

The homogeneous matrix from frame 0 to frame 3 is:

4-frame-0-to-frame-3JPG

Let’s pull out the rotation matrix:

5-rotation-matrix-frame-3-to-frame-0JPG

Let’s go through the matrix to see if it makes sense. Here is the diagram:

13-cartesian-robotJPG

In the first column of the matrix, we see that the value on the third row is 1. It is saying that the x3 vector is in the same direction as z0. If we look at the diagram, we can see that this is in fact the case.

In the second column of the matrix, we see that the value on the first row is -1. It is saying that the y3 vector is in the opposite direction as x0. If we look at the diagram, we can see that this is in fact the case.

In the third column of the matrix, we see that the value on the second row is -1. It is saying that the z3 vector is in the opposite direction as y0. If we look at the diagram, we can see that this is in fact the case.

Finally, in the fourth column of the matrix, we have the displacement vector. Let’s pull that out.

6-displacement-vector-frame-3-to-frame-0JPG

The displacement vector portion of the matrix says that the position of the end effector of the robot is 2 units along x0, -2 units along y0, and 2 units along z0. These results make sense given the link lengths and displacements were 1.

Example 2 – Six Degree of Freedom Robotic Arm

Let’s take a look at another example, a six degree of freedom robotic arm.

6dof-diy-robotic-arm
38-add-y-axisJPG

Here is the code:

import numpy as np # Scientific computing library

# Project: Coding Denavit-Hartenberg Tables Using Python - 6DOF Robotic Arm
#          This code excludes the servo motor that controls the gripper.
# Author: Addison Sears-Collins
# Date created: August 22, 2020

# Link lengths in centimeters
a1 = 1 # Length of link 1
a2 = 1 # Length of link 2
a3 = 1 # Length of link 3
a4 = 1 # Length of link 4
a5 = 1 # Length of link 5
a6 = 1 # Length of link 6

# Initialize values for the joint angles (degrees)
theta_1 = 0 # Joint 1
theta_2 = 0 # Joint 2
theta_3 = 0 # Joint 3
theta_4 = 0 # Joint 4
theta_5 = 0 # Joint 5

# Declare the Denavit-Hartenberg table. 
# It will have four columns, to represent:
# theta, alpha, r, and d
# We have the convert angles to radians.
d_h_table = np.array([[np.deg2rad(theta_1), np.deg2rad(90), 0, a1],
                      [np.deg2rad(theta_2), 0, a2, 0],
                      [np.deg2rad(theta_3), 0, a3, 0],
                      [np.deg2rad(theta_4 + 90), np.deg2rad(90), a5,0],
                      [np.deg2rad(theta_5), 0, 0, a4 + a6]]) 

# Homogeneous transformation matrix from frame 0 to frame 1
i = 0
homgen_0_1 = np.array([[np.cos(d_h_table[i,0]), -np.sin(d_h_table[i,0]) * np.cos(d_h_table[i,1]), np.sin(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.cos(d_h_table[i,0])],
                      [np.sin(d_h_table[i,0]), np.cos(d_h_table[i,0]) * np.cos(d_h_table[i,1]), -np.cos(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.sin(d_h_table[i,0])],
                      [0, np.sin(d_h_table[i,1]), np.cos(d_h_table[i,1]), d_h_table[i,3]],
                      [0, 0, 0, 1]])  

# Homogeneous transformation matrix from frame 1 to frame 2
i = 1
homgen_1_2 = np.array([[np.cos(d_h_table[i,0]), -np.sin(d_h_table[i,0]) * np.cos(d_h_table[i,1]), np.sin(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.cos(d_h_table[i,0])],
                      [np.sin(d_h_table[i,0]), np.cos(d_h_table[i,0]) * np.cos(d_h_table[i,1]), -np.cos(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.sin(d_h_table[i,0])],
                      [0, np.sin(d_h_table[i,1]), np.cos(d_h_table[i,1]), d_h_table[i,3]],
                      [0, 0, 0, 1]])  

# Homogeneous transformation matrix from frame 2 to frame 3
i = 2
homgen_2_3 = np.array([[np.cos(d_h_table[i,0]), -np.sin(d_h_table[i,0]) * np.cos(d_h_table[i,1]), np.sin(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.cos(d_h_table[i,0])],
                      [np.sin(d_h_table[i,0]), np.cos(d_h_table[i,0]) * np.cos(d_h_table[i,1]), -np.cos(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.sin(d_h_table[i,0])],
                      [0, np.sin(d_h_table[i,1]), np.cos(d_h_table[i,1]), d_h_table[i,3]],
                      [0, 0, 0, 1]])  

# Homogeneous transformation matrix from frame 3 to frame 4
i = 3
homgen_3_4 = np.array([[np.cos(d_h_table[i,0]), -np.sin(d_h_table[i,0]) * np.cos(d_h_table[i,1]), np.sin(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.cos(d_h_table[i,0])],
                      [np.sin(d_h_table[i,0]), np.cos(d_h_table[i,0]) * np.cos(d_h_table[i,1]), -np.cos(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.sin(d_h_table[i,0])],
                      [0, np.sin(d_h_table[i,1]), np.cos(d_h_table[i,1]), d_h_table[i,3]],
                      [0, 0, 0, 1]])  

# Homogeneous transformation matrix from frame 4 to frame 5
i = 4
homgen_4_5 = np.array([[np.cos(d_h_table[i,0]), -np.sin(d_h_table[i,0]) * np.cos(d_h_table[i,1]), np.sin(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.cos(d_h_table[i,0])],
                      [np.sin(d_h_table[i,0]), np.cos(d_h_table[i,0]) * np.cos(d_h_table[i,1]), -np.cos(d_h_table[i,0]) * np.sin(d_h_table[i,1]), d_h_table[i,2] * np.sin(d_h_table[i,0])],
                      [0, np.sin(d_h_table[i,1]), np.cos(d_h_table[i,1]), d_h_table[i,3]],
                      [0, 0, 0, 1]])  

homgen_0_5 = homgen_0_1 @ homgen_1_2 @ homgen_2_3 @ homgen_3_4 @ homgen_4_5 

# Print the homogeneous transformation matrices
print("Homogeneous Matrix Frame 0 to Frame 5:")
print(homgen_0_5)

Now, run the code:

Here is the output:

7-here-is-the-outputJPG

In matrix form, this is:

8-in-matrix-formJPG

Does this make sense?  Here is the diagram:

38-add-y-axisJPG

In the first column of the matrix, we see that the value on the third row is 1. It is saying that the x5 vector is in the same direction as z0. If we look at the diagram, we can see that this is in fact the case.

In the second column of the matrix, we see that the value on the second row is -1. It is saying that the y5 vector is in the opposite direction as y0. If we look at the diagram, we can see that this is in fact the case.

In the third column of the matrix, we see that the value on the first row is 1. It is saying that the z5 vector is in the same direction as x0. If we look at the diagram, we can see that this is in fact the case.

Finally, in the fourth column of the matrix, we have the displacement vector. This portion of the matrix says that the position of the end effector of the robot is 4 units along x0, 0 units along y0, and 2 units along z0. These results make sense given that we set all the link lengths to 1.

References

Credit to Professor Angela Sodemann from whom I learned these important robotics fundamentals. Dr. Sodemann teaches robotics over at her website, RoboGrok.com. While she uses the PSoC in her work, I use Arduino and Raspberry Pi since I’m more comfortable with these computing platforms. Angela is an excellent teacher and does a fantastic job explaining various robotics topics over on her YouTube channel.

Homogeneous Transformation Matrices Using Denavit-Hartenberg

Once we have filled in the Denavit-Hartenberg (D-H) parameter table for a robotic arm, we find the homogeneous transformation matrices (also known as the Denavit-Hartenberg matrix) by plugging the values into the matrix of the following form, which is the homogeneous transformation matrix for joint n (i.e. the transformation from frame n-1 to frame n).

1-homogeneous-n-1-nJPG

where R is the 3×3 submatrix in the upper left that represents the rotation from frame n-1 (e.g. frame 0) to frame n (e.g. frame 1), and T is the 3×1 submatrix in the upper right that represents the translation (or displacement) from frame n-1 to frame n.

For example, suppose we have a SCARA robotic arm.

2-scara-robot-arm-denavit-hartenbergJPG
29-scara-robot

We draw the kinematic diagram for this arm.

33-add-y-axisJPG

We then use that diagram to find the Denavit-Hartenberg parameters:

2-scara-robot-arm-denavit-hartenbergJPG-1

We now want to find the homogeneous transformation matrix from frame 0 to frame 1, so we look at the first row of the Denavit-Hartenberg parameter table labeled ‘Joint 1’ (remember that a joint in our case is either a servo motor that produces rotational motion or a linear actuator that produces linear motion). 

In this case, n=1, and we would look at the first row of the D-H table (Joint 1) and plug in the appropriate values into the following matrix:

3-plug-in-values-for-matrixJPG

For the homogeneous transformation matrix from frame 1 to 2, we would look at the second row of the D-H table (Joint 2) and plug in the corresponding values into the following matrix.

4-plug-in-correspondingJPG

For the homogeneous transformation matrix from frame 2 to 3, we would look at the third row of the table (Joint 3) and plug in the corresponding values into the following matrix.

5-look-at-third-rowJPG

Then, to find the homogeneous transformation matrix from the base frame (frame 0) to the end-effector frame (frame 3), we would multiply all the transformation matrices together.

homgen_0_3 = (homgen_0_1)(homgen_1_2)(homgen_2_3)

Let’s take a look at some examples.

Example 1 – Cartesian Robot

15-example-of-cartesian-robot
13-cartesian-robotJPG

We have four reference frames, so we need to have three rows in our Denavit-Hartenberg parameter table.

6-four-reference-framesJPG

Let’s begin by looking at the first column of the table. 

Find θ

13-cartesian-robotJPG

For the Joint 1 row (Servo 0), we are going to focus on the relationship between frame 0 and frame 1. θ is the angle from x0 to x1 around z0.

If you look at the diagram, take the thumb of your right hand and stick it in z0 direction. Your fingers curl in the direction of positive rotation. The angle from x0 to x1 around z0 is 90 degrees in the counterclockwise (i.e. positive) direction. This angle won’t change regardless of how the linear actuator at frame 0 moves in the d1 direction.

7-theta-1JPG

Now, let’s look at the Joint 2 row. We take a look at the rotation between frame 1 and frame 2. θ is the angle from x1 to x2 around z1.

If you look at the diagram, take the thumb of your right hand and stick it in z1 direction. Your fingers curl in the direction of positive rotation. The angle from x1 to x2 around z1 is 90 degrees in the counterclockwise (i.e. positive) direction. This angle won’t change regardless of how the linear actuator at frame 1 moves in the d2 direction.

8-90-degreesJPG

Now, let’s look at the Joint 3 row. We take a look at the rotation between frame 2 and frame 3. θ is the angle from x2 to x3 around z2.

If you look at the diagram, x2 and x3 both point in the same direction. The axes are therefore aligned. When the robot is in motion, there is only linear motion along z2. The angle from x2 to x3 around z2 will remain 0, so let’s put that in the third row of our table.

9-third-rowJPG

Find α

13-cartesian-robotJPG

Let’s start with the Joint 1 row of the table.

α is the angle from z0 to z1 around x1.

Take your right thumb and point it in the x1 direction. Curl your fingers counterclockwise from z0 to z1. The angle is 90 degrees.

10-find-alphaJPG-1

Let’s go to the Joint 2 row of the table.

α is the angle from z1 to z2 around x2. Take your right thumb, and stick it in the x2 direction. We would have to rotate 90 degrees in the clockwise (i.e. negative) direction to go from z1 to z2.

11-joint-2-rowJPG

Let’s go to the Joint 3 row of the table.

α is the angle from z2 to z3 around x3. In the kinematic diagram, you can see that this angle is 0 degrees, so we put 0 in the table.

12-alpha-last-rowJPG

Find r

13-cartesian-robotJPG

Let’s start with the Joint 1 row of the table.

r is the distance between the origin of frame 0 and the origin of frame 1 along the x1 direction. You can see in the diagram that this distance is 0.

13-find-rJPG-1

Now let’s look at the Joint 2 row. r is the distance between the origin of frame 1 and the origin of frame 2 along the x2 direction. You can see in the diagram that this distance is 0.

14-find-rJPG

Now let’s look at the Joint 3 row. r is the distance between the origin of frame 2 and the origin of frame 3 along the x3 direction. You can see in the diagram that this distance is 0.

15-find-rJPG

Find d

13-cartesian-robotJPG

Now let’s find d. We’ll start on the first row of the table as usual.

d is the distance from x0 to x1 along the z0 direction. You can see that this distance is a1 + d1. a1 is the distance between the origin of frame 0 and the origin of frame 1 when the linear actuator (i.e. motor that generates linear motion) is in its home position, unextended. d1 is the distance the actuator extends beyond the home position.

16-find-dJPG-1


Now let’s take a look at frame 1 to frame 2. d is the distance from x1 to x2 along the z1 direction. You can see that this distance is a2 + d2.

17-find-dJPG

Now let’s take a look at frame 2 to frame 3. d is the distance from x2 to x3 along the z2 direction. You can see that this distance is a3 + d3.

18-find-dJPG

To check your work, all of the link lengths and all of the joint variables in the kinematic diagram should appear in the Denavit-Hartenberg table.

Example 2 – Articulated Robot

23-example-of-articulated-robot
21-articulated-manipulatorJPG

We have four reference frames, so we need to have three rows in our Denavit-Hartenberg parameter table.

19-articulated-robotJPG

Let’s begin by looking at the first column of the table. 

Find θ

21-articulated-manipulatorJPG

For the Joint 1 row (Servo 0), we are going to focus on the relationship between frame 0 and frame 1. θ is the angle from x0 to x1 around z0.

If you look at the diagram, take the thumb of your right hand and stick it in z0 direction. Your fingers curl in the direction of positive rotation. The angle from x0 to x1 around z0 is θ1 degrees in the counterclockwise (i.e. positive) direction.

20-find-thetaJPG

Now, let’s look at the Joint 2 row. We take a look at the rotation between frame 1 and frame 2. θ is the angle from x1 to x2 around z1.

If you look at the diagram, take the thumb of your right hand and stick it in z1 direction. Your fingers curl in the direction of positive rotation. The angle from x1 to x2 around z1 is θ2 degrees in the counterclockwise (i.e. positive) direction.

21-theta-2JPG

Now, let’s look at the Joint 3 row. We take a look at the rotation between frame 2 and frame 3. θ is the angle from x2 to x3 around z2.

If you look at the diagram, x2 and x3 both point in the same direction. The axes are therefore aligned. When the robot is in motion, the angle from x2 to x3 around z2 will be θ3 degrees, so let’s put that in the third row of our table.

22-theta-3JPG

Find α

21-articulated-manipulatorJPG

Let’s start with the Joint 1 row of the table.

α is the angle from z0 to z1 around x1.

Take your right thumb and point it in the x1 direction. Curl your fingers counterclockwise from z0 to z1. The angle is 90 degrees.

23-alphaJPG

Let’s go to the Joint 2 row of the table.

α is the angle from z1 to z2 around x2. Take your right thumb, and stick it in the x2 direction. The angle between z1 and z2 is 0 degrees since both point in the same direction.

24-alpha-joint-2JPG

Let’s go to the Joint 3 row of the table.

α is the angle from z2 to z3 around x3. In the kinematic diagram, you can see that this angle is 0 degrees, so we put 0 in the table.

25-alpha-joint-3JPG

Find r

21-articulated-manipulatorJPG

Let’s start with the Joint 1 row of the table.

r is the distance between the origin of frame 0 and the origin of frame 1 along the x1 direction. You can see in the diagram that this distance is 0.

26-find-rJPG

Now let’s look at the Joint 2 row. r is the distance between the origin of frame 1 and the origin of frame 2 along the x2 direction. You can see in the diagram that this distance is a2.

27-find-rJPG

Now let’s look at the Joint 3 row. r is the distance between the origin of frame 2 and the origin of frame 3 along the x3 direction. You can see in the diagram that this distance is a3.

28-find-rJPG

Find d

21-articulated-manipulatorJPG

Now let’s find d. We’ll start on the first row of the table as usual.

d is the distance from x0 to x1 along the z0 direction. You can see that this distance is a1. a1 is the distance between the origin of frame 0 and the origin of frame 1. No matter how the servos move, this distance will always remain a1.

29-find-dJPG

Now let’s take a look at frame 1 to frame 2. d is the distance from x1 to x2 along the z1 direction. You can see that this distance is 0.

30-find-dJPG

Now let’s take a look at frame 2 to frame 3. d is the distance from x2 to x3 along the z2 direction. You can see that this distance is 0.

31-find-dJPG

To check your work, all of the link lengths and all of the joint variables in the kinematic diagram should appear in the Denavit-Hartenberg table.

Example 3 – Six Degree of Freedom Robotic Arm

6-dof-robotic-arm-2
38-add-y-axisJPG

We have six reference frames, so we need to have five rows in our Denavit-Hartenberg parameter table. 

See if you can do this one all by yourself, and then use the table below to check your work. Remember the rules:

  • θ is the angle from xn-1 to xn around zn-1.
  • α is the angle from zn-1 to zn around xn.
  • r (sometimes you’ll see the letter ‘a’ instead of ‘r’) is the distance between the origin of the n-1 frame and the origin of the n frame along the xn direction.
  • d is the distance from xn-1 to xn along the zn-1 direction.
32-example-6-dof-robotic-arm-denavit-hartenbergJPG

Example 4 – Six Degree of Freedom Collaborative Robot

39-6dof-collaborative-robotJPG
40-kinematic-diagram-collaborative-robot-ur5JPG

We have seven reference frames, so we need to have six rows in our Denavit-Hartenberg parameter table. 

See if you can do this one all by yourself, and then use the table below to check your work. Remember the rules:

  • θ is the angle from xn-1 to xn around zn-1.
  • α is the angle from zn-1 to zn around xn.
  • r (sometimes you’ll see the letter ‘a’ instead of ‘r’) is the distance between the origin of the n-1 frame and the origin of the n frame along the xn direction.
  • d is the distance from xn-1 to xn along the zn-1 direction.
33-6dof-collaborative-robotJPG

A few things to note:

  • We have negative values for θ above due to the clockwise rotation about the zn-1 axis.
  • I also didn’t use all of the a variables in the diagram because some of these measurements are irrelevant for calculating the Denavit-Hartenberg parameter table.
  • Displacement is a vector quantity, which means it has both a magnitude and a direction. You’ll therefore see negative values for a in the table above.

Example 5 – Six Degree of Freedom Industrial Robot

41-fanuc-lrmate-200idJPG
42-denavit-hartenberg-frames-fanuc-lrmate-200idJPG

We have seven reference frames, so we need to have six rows in our Denavit-Hartenberg parameter table. 

See if you can do this one all by yourself, and then use the table below to check your work. Remember the rules:

  • θ is the angle from xn-1 to xn around zn-1.
  • α is the angle from zn-1 to zn around xn.
  • r (sometimes you’ll see the letter ‘a’ instead of ‘r’) is the distance between the origin of the n-1 frame and the origin of the n frame along the xn direction.
  • d is the distance from xn-1 to xn along the zn-1 direction.
34-6dof-industrial-robotJPG

Remember when you’re trying to find theta that rotation in the counterclockwise direction (as viewed from looking down on the axis of rotation) is positive. Otherwise, it is negative.

You point your thumb in the direction of the axis of rotation and curl your fingers. Your finger-curl direction is positive rotation.

References

Credit to Professor Angela Sodemann from whom I learned these important robotics fundamentals. Dr. Sodemann teaches robotics over at her website, RoboGrok.com. While she uses the PSoC in her work, I use Arduino and Raspberry Pi since I’m more comfortable with these computing platforms. Angela is an excellent teacher and does a fantastic job explaining various robotics topics over on her YouTube channel.

How to Find Denavit-Hartenberg Parameter Tables

In this section, we’ll learn how to find the Denavit-Hartenberg Parameter table for robotic arms. This method is a shortcut for finding homogeneous transformation matrices and is commonly seen in documentation for industrial robots as well as in the research literature. The real-world example we’ll consider in this tutorial is a SCARA robotic arm, like the one below.

scara-robot-packaging-cookies

Remember that homogeneous transformation matrices enable you to express the position and orientation of the end effector frame (e.g. robotics gripper, hand, vacuum suction cup, etc.) in terms of the base frame. 

To calculate the homogeneous transformation matrix from the base frame to the end effector frame, the only values you need to have are the length of each link and the angle of each servo motor.

The Three Steps

Here are the three steps for finding the Denavit-Hartenbeg parameter table and the homogeneous transformation matrices for a robotic manipulator:

1. Draw the kinematic diagram according to the four Denavit-Hartenberg rules.

2. Create the Denavit-Hartenberg parameter table.

  • Number of Rows = Number of Frames – 1
  • Number of Columns = 4: Two columns for rotation and two columns for displacement

3. Find the homogeneous transformation matrices (I’ll cover how to do this step in my next post).

Definition of the Parameters

The Denavit-Hartenberg parameter tables consist of four variables:

  • The two variables used for rotation are θ and α.
  • The two variables used for displacement are r and d.

Here is the D-H parameter table template for a robotic arm with four reference frames:

1-denavit-hartenberg-parameters-table-templateJPG

Let’s take a look at what these parameters mean by looking at two different frames. The n-1 frame is the frame before the n frame. We assume that both frames are connected by a link. 

For example, if the n-1 frame is frame 2, the n frame is frame 3.

2-n-1-and-n-frameJPG

θ is the angle from xn-1 to xn around zn-1.

3-theta-is-the-angleJPG

α is the angle from zn-1 to zn around xn.

4-alpha-is-the-angleJPG

r (sometimes you’ll see the letter ‘a’ instead of ‘r’) is the distance between the origin of the n-1 frame and the origin of the n frame along the xn direction.

d is the distance from xn-1 to xn along the zn-1 direction.

5-r-and-dJPG

Example 1 – Two Degree of Freedom Robotic Arm

22-beam-mount-pointing-right

Let’s take a look at an example so that we can walk through the process of creating and filling in Denavit-Hartenberg parameter tables.

Draw the Kinematic Diagram According to the Denavit-Hartenberg Rules

We’ll start by drawing the kinematic diagram of a two degree of freedom robotic arm.

6-kinematic-diagram-2dofJPG

Create the Denavit-Hartenberg Parameter Table

Now, we need to find the Denavit-Hartenberg parameters. We have three coordinate frames here, so we need to have two rows in our D-H table (i.e. number of rows = number of frames – 1).

7-two-rowsJPG

Find θ 

For the Joint 1 (Servo 0) row, we are going to focus on the relationship between frame 0 and frame 1. θ is the angle from x0 to x1 around z0.

If you look at the diagram, x0 and x1 both point in the same direction. The axes are therefore aligned. When the robot is in motion, θ1 will change (which will cause frame 1 to move relative to frame 0). The angle from x0 to x1 around z0 will be θ1, so let’s put that in our table.

8-find-thetaJPG

Now, let’s look at the Joint 2 (Servo 1) row. We take a look at the rotation between frame 1 and frame 2. θ is the angle from x1 to x2 around z1.

If you look at the diagram, x1 and x2 both point in the same direction. The axes are therefore aligned. When the robot is in motion, θ2 will change (which will cause frame 2 to move). The angle from x1 to x2 around z1 will be θ2, so let’s put that in the second row of our table.

9-theta-2JPG

Find α

Let’s start with the Joint 1 (Servo 0) row of the table.

α is the angle from z0 to z1 around x1.

10-find-alphaJPG

In the diagram above, you can see that this angle is 90 degrees, so we put 90 in the table.

11-put-90-in-tableJPG

Let’s go to the Joint 2 row of the table.

α is the angle from z1 to z2 around x2. You can see that no matter what happens to θ2, the angle from z1 to z2 will be 0 (since both axes point in the same direction). We put 0 degrees into the table.

12-put-0-degreesJPG

Find r

13-find-rJPG

Let’s start with the Joint 1 row of the table.

r is the distance between the origin of frame 0 and the origin of frame 1 along the x1 direction. You can see in the diagram that this distance is 0.

14-distance-is-0JPG

Now let’s look at the Joint 2 row. r is the distance between the origin of frame 1 and the origin of frame 2 along the x2 direction. You can see in the diagram that this distance is a2.

15-distance-is-a2JPG

Find d

16-find-dJPG

Now let’s find d. We’ll start on the first row of the table as usual.

d is the distance from x0 to x1 along the z0 direction. You can see that this distance is a1.

17-distance-is-a1JPG

Now let’s take a look at frame 1 to frame 2. d is the distance from x1 to x2 along the z1 direction. You can see that this distance is 0.

Example 2 – SCARA Robot

29-scara-robot

Let’s get some more practice filling in D-H parameter tables by looking at the SCARA robot.

Draw the Kinematic Diagram According to the Denavit-Hartenberg Rules

Here is the kinematic diagram using the D-H convention.

33-add-y-axisJPG

Create the Denavit-Hartenberg Parameter Table

Now, we need to find the Denavit-Hartenberg parameters. We have four coordinate frames here, so we need to have three rows in our D-H table.

18-d-h-table-scara-robotJPG

Find θ

33-add-y-axisJPG

For the Servo 0 row, we are going to focus on the relationship between frame 0 and frame 1. θ is the angle from x0 to x1 around z0.

If you look at the diagram, x0 and x1 both point in the same direction. The axes are therefore aligned. When the robot is in motion, θ1 will change (which will cause frame 1 to move). The angle from x0 to x1 around z0 will be θ1, so let’s put that in our table.

19-theta-1JPG

Now, let’s look at the Servo 1 row. We take a look at the rotation between frame 1 and frame 2. θ is the angle from x1 to x2 around z1.

If you look at the diagram, x1 and x2 both point in the same direction. The axes are therefore aligned. When the robot is in motion, θ2 will change (which will cause frame 2 to move). The angle from x1 to x2 around z1 will be θ2, so let’s put that in the second row of our table.

20-theta-2JPG

Now, let’s look at the Servo 2 row. We take a look at the rotation between frame 2 and frame 3. θ is the angle from x2 to x3 around z2.

If you look at the diagram, x2 and x3 both point in the same direction. The axes are therefore aligned. When the robot is in motion, there is only linear motion along z2. The angle from x2 to x3 around z2 will remain 0, so let’s put that in the third row of our table.

21-add-0JPG

Find α

33-add-y-axisJPG

Let’s start with the Servo 0 row of the table.

α is the angle from z0 to z1 around x1.

In the diagram above, you can see that this angle is 0 degrees, so we put 0 in the table.

22-find-alphaJPG

Let’s go to the Servo 1 row of the table.

α is the angle from z1 to z2 around x2. In the diagram above, you can see that this angle is 180 degrees, so we put 180 in the table.

23-row-2JPG

Let’s go to the Servo 2 row of the table.

α is the angle from z2 to z3 around x3. In the diagram above, you can see that this angle is 0 degrees, so we put 0 in the table.

24-put-in-0JPG

Find r

33-add-y-axisJPG

Let’s start with the Servo 0 row of the table.

r is the distance between the origin of frame 0 and the origin of frame 1 along the x1 direction. You can see in the diagram that this distance is a2.

25-start-rJPG

Now let’s look at the Servo 1 row. r is the distance between the origin of frame 1 and the origin of frame 2 along the x2 direction. You can see in the diagram that this distance is a4.

26-a-4JPG

Now let’s look at the Servo 2 row. r is the distance between the origin of frame 2 and the origin of frame 3 along the x3 direction. You can see in the diagram that this distance is 0.

27-last-row-rJPG

Find d

Now let’s find d. We’ll start on the first row of the table as usual.

d is the distance from x0 to x1 along the z0 direction. You can see that this distance is a1.

28-start-dJPG

Now let’s take a look at frame 1 to frame 2. d is the distance from x1 to x2 along the z1 direction. You can see that this distance is a3.

29-second-row-dJPG

Now let’s take a look at frame 2 to frame 3. d is the distance from x2 to x3 along the z2 direction. You can see that this distance is a5 + d3.

30-last-rowJPG

References

Credit to Professor Angela Sodemann for teaching me this stuff. She is an excellent teacher (She runs a course on RoboGrok.com). On her YouTube channel, she provides some of the clearest explanations on robotics fundamentals you’ll ever hear.