"

3 Forward Kinematics for Serial Manipulators

Elissa Ledoux

1) Basics of Forward Kinematics

Theory

Forward kinematics maps a robot’s joint positions to its end effector pose.  It describes a manipulator’s motion irrespective of force and torque.

forward kinematics
Figure 3.1: Forward Kinematics

For simplicity, assume each joint in the chain has 1 DoF (or is two joints, etc.).  For serial manipulators, place a coordinate frame on each joint, and number the joints in order from base to tip.  The robot’s base is considered link 0, so the first joint (joint 1) drives link 1, joint 2 drives link 2, etc.  The Z axis of each joint should indicate the axis of motion.  An example robot (ABB IRB 6700) is shown below, with coordinate frames attached to each joint.

Standard 6-Axis Industrial Robot with Coordinate Frames
Figure 3.2: Standard 6-Axis Industrial Robot with Coordinate Frames

For a detailed introduction to forward kinematics, watch the Forward Kinematics Introduction video below.

Video: Forward Kinematics Intro (click link for closed caption version)

There are three common methods of solving for a robot’s forward kinematics equations.  These are:

  1. Basic Method
  2. Denavit-Hartenberg (DH) Method
  3. Product of Exponentials (PE) Method

The basic method is used for simple robots, generally those that have three or fewer joints.  The DH and PE methods are used for more complicated robots.  Each section of this chapter will cover a different method of forward kinematics, with theory and examples.

The procedure for the basic method of forward kinematics is as follows:

  1. Put one coordinate frame on each link
  2. Find the link positions o_1^0o_n^0
  3. Find the end effector frame orientation R_n^0
  4. Make the homogeneous transformation T_n^0 = \begin{bmatrix} R_n^0 & o_n^0 \\ 0_{1x3} & 1 \end{bmatrix}

Examples

For a detailed explanation and example of forward kinematics for a two-link RR robot, see the video below.

Video: Forward Kinematics – Basic Method (click link for closed caption version)

Quick Quiz

2) Denavit-Hartenberg (DH) Method

Theory

The Denavit-Hartenberg (DH) method of forward kinematics uses a current-frame approach. Each transformation from one coordinate frame to another is represented by the product of four basic transformations:

  1. Rotation around current Z by angle \theta (“joint angle”)
  2. Translation along current Z by distance d (“link offset”)
  3. Translation along current X by distance a (“link length”)
  4. Rotation around current X by angle \alpha (“link twist”)

    $T_i^{i-1} = [Rot_{z,\theta_i}] [Trans_{z,d_i}] [Trans_{x,a_i}] [Rot_{x,\alpha_i}]  \\ \\ $ $T_i^{i-1} = \left\[ \begin{bmatrix} c_{\theta i} & -s_{\theta i}c_{\alpha i} & s_{\theta i}s_{\alpha i} & a_i c_{\theta i} \\ s_{\theta i} & c_{\theta i}c_{\alpha i} & -c_{\theta i}s_{\alpha i} & a_i s_{\theta i} \\ 0 & s_{\alpha i} & c_{\alpha i} & d_i\\ 0 & 0 & 0 & 1 \end{bmatrix} = \begin{bmatrix} R_i^{i-1} & o_i^{i-1} \\ 0_{1x3} & 1 \end{bmatrix} \right\]$

In layman’s terms, this transformation tells you the orientation and position coordinates of the robot’s current joint location relative to the previous one.  This is illustrated in the following diagram:

DH Frame Diagram
Figure 3.3: DH Frame Diagram

where the parameter assignments are:

  • \theta_i joint angle: angle from x_{i-1} to x_i around z_{i-1}
  • d_i joint angle: angle from x_{i-1} to x_i along z_{i-1}
  • a_i joint angle: angle from z_{i-1} to z_i along x_i
  • \alpha_i joint angle: angle from z_{i-1} to z_i around x_i

There are a few special cases for parameter assignment.

  1. If z_{i-1} and z_i are not coplanar:
    x_i goes from z_{i-1} to z_i perpendicularly
  2. If z_{i-1} and z_i are parallel:
    x_i goes along link i-1
  3. If z_{i-1} and z_i intersect:
    x_i is perpendicular to that plane

This theory is explained in the video below.

Video: Forward Kinematics – Denavit-Hartenberg (DH) Method (click link for closed caption version)

Once the parameter definitions and mathematical rules are understood, the procedure for actually determining the forward kinematics equations is:

  1. Identify joint axes z_i (1 per joint)
  2. Attach coordinate frames (1 per link, x_i on link)
  3. Identify and tabulate DH parameters
  4. Determine link transformations T_i^{i-1}
  5. Multiply all T‘s to obtain T_n^0 = T_1^0 T_2^1 ... T_n^{n-1}

T_n^0 = T_1^0 T_2^1 ... T_n^{n-1} = \begin{bmatrix} R_n^0 & o_n^0 \\ 0 & 1 \end{bmatrix}

Keep in mind that while these transformations are extremely tedious and complicated to find by hand, they can be calculated very efficiently in Matlab by writing a function for the transformation matrix and using the DH parameters obtained in step 3 as inputs.

Examples

To demonstrate how to apply this theory to physical robots, two example videos are included.  The first video below shows how to derive the DH parameters for a RPP cylindrical robot:

Video: FK Example – DH Method – RPP Cylindrical Robot (click link for closed caption version)

The following video shows how to derive the DH parameters for an RRR spherical wrist (the distal half of a standard 6-axis robot):

Video: FK Example – DH Method – RRR Spherical Wrist (click link for closed caption version)

Quick Quiz

3) Product of Exponentials Method

Theory

The Product of Exponentials (PE) method of forward kinematics uses the axis-angle formulation with \hat\omega instead of \hat{k} symbolizing the axis of rotation.  For this method, math is done in the fixed (world) coordinate frame.  The PE formula to find the transformation expressing the tip pose in the base frame is:

T_n^0 (\theta) = e^{\hat{\xi_1}\theta_1} e^{\hat{\xi_2}\theta_2} ... e^{\hat{\xi_n}\theta_n} T_n^0 (0)

where T_n^0 (0) is the robot’s home configuration (when all joint angles = 0) and e^{\hat{\xi_i}\theta_i} is the 4×4 transformation for link i. The subscripts 0 represents base frame and n represents tip frame.  The squiggle \xi is the Greek letter “xi” and is different than \zeta (“zeta”).  In layman’s terms, this transformation tells you the orientation and position coordinates of the robot’s tip relative to its base frame.

The procedure for implementing the product of exponentials method is as follows.

  1. Assign coordinate frames (base 0 and tip n), link velocities (\hat\omega‘s) and joint positions (d’s, \theta‘s).
  2. Place p‘s (initial points)
  3. Find home configuration T_n^0 (0)
  4. Calculate twists (\xi‘s and \hat\xi‘s)
  5. Use the product of exponentials formula e^{\hat{\xi_i}\theta_i} to build the base-to-tip transformation matrix

T_n^0 (\theta) = e^{\hat{\xi_1}\theta_1} e^{\hat{\xi_2}\theta_2} ... e^{\hat{\xi_n}\theta_n} T_n^0 (0)

This theory is explained in the video below.

Video: Forward Kinematics – Product of Exponentials Method (click link for closed caption version)

The steps to implement the PE method of forward kinematics are detailed below:

Step 1: Assign coordinate frames (base 0 and tip n), link velocities (\hat\omega‘s) and joint positions (d’s, \theta‘s).

  • Only assign coordinate frames for the links whose location in 3D space matters.
    • If all that matters is the end effector location, only assign frames for base and tip.
    • If simulating the entire robot (and all links need to be plotted), assign frames for all links.
  • \hat\omega points along the Z axis (\hat{k}) of the joint.  It is a unit vector for revolute joints and 0 for prismatic joints since a prismatic joint has no angular velocity.
  • and \theta are positive in the +Z direction.
  • Remember that all coordinates are given in the world frame (fixed frame, base frame).

Step 2: Place p‘s (initial points)

  • Place these anywhere along the joint’s Z axis.
  • The most intuitive placement is on each joint frame origin.
  • These values should be declared as constant parameters from the initial configuration, no need to account for joint motion.

Step 3: Find home configuration T_n^0 (0)

  • R_n^0 is a rotation you must determine from the relative orientations of the base and tip frames.  Look at the two frames and see what rotations need to be done to go from base to tip.  If the base and tip frames point in the same direction in this initial configuration, then R_n^0 is just the identity matrix.
  • o_n^0 should be the same as p for the tip
  • T_n^0 = \begin{bmatrix} R_n^0 & o_n^0 \\ 0 & 1 \end{bmatrix}

Step 4: Calculate twist coordinates (\xi‘s) and twists (\hat\xi‘s)

  • These represent joint velocities.
  • For revolute joints: calculate these from \hat\omega and p.
  • For prismatic joints: calculate these from v.
  • Formulas for the angular velocity vectors, twist coordinates, and twists are shown in the table below:
Prismatic Joints Revolute Joints
Angular velocity \vec\omega: n/a \vec\omega = \begin{bmatrix} \omega_x \\ \omega_y \\ \omega_z \end{bmatrix}
Hatted ang vel \hat\omega: n/a \hat\omega = \begin{bmatrix} 0 & -\omega_z & \omega_y \\ \omega_z & 0 & -\omega_x \\ -\omega_y & \omega_x & 0 \end{bmatrix}
Twist coordinates (\xi): \xi = \begin{bmatrix} \vec{v} \\ 0 \end{bmatrix} (6×1 matrix) \xi = \begin{bmatrix} -\omega \times p \\ \vec{\omega} \end{bmatrix} (6×1 matrix)
Twists (\hat\xi): \hat\xi = \begin{bmatrix} 0 & v \\ 0 & 0 \end{bmatrix} (4×4 matrix) \hat\xi = \begin{bmatrix} \hat{\omega} & -\omega \times p \\ 0 & 0 \end{bmatrix} (4×4 matrix)

Keep in mind that sometimes 0 represents the matrix 0 depending on the elements to fill.  The subscript i represents the joint number.

Step 5: Use the product of exponentials formula e^{\hat{\xi_i}\theta_i} to build the base-to-tip transformation matrix

T_n^0 (\theta) = e^{\hat{\xi_1}\theta_1} e^{\hat{\xi_2}\theta_2} ... e^{\hat{\xi_n}\theta_n} T_n^0 (0)

Keep in mind that while these calculations are extremely tedious and complicated to do by hand, they can be very efficiently simulated in Matlab by writing functions for steps 4 and 5 of the analysis and calling them in a script after defining and using the parameters obtained from steps 1-3.

Examples

These next few examples show how to perform forward kinematics analysis for serial robots using the Product of Exponentials method.  The first video demonstrates an RPP cylindrical robot, the same robot from the example above using the DH method, but this time taking a new approach to analysis.

Video: FK Example – Prod Exp Method – RPP Cylindrical Robot (click link for closed caption version)

This next example covers PE FK analysis of a 6-DOF standard cobot arm.

Video: FK Example – Prod Exp Method – 6R UR Robot (click link for closed caption version)

Quick Quiz

License

Icon for the Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International License

Robotics and Controls Engineering Copyright © by Hongbo Zhang; Elissa Ledoux; and Vishwas Bedekar is licensed under a Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International License, except where otherwise noted.