Module 5: Applications Lesson 1 of 3

Forward Kinematics

A robot arm is a chain of rigid links connected by joints. The fundamental question of forward kinematics is: given the joint angles, where is the end-effector? This lesson shows how everything we’ve learned — rotation matrices, homogeneous transforms, and matrix multiplication — comes together to answer that question systematically.

The Problem

Consider a serial robot arm with nn joints. Each joint has a variable qiq_i (angle for revolute joints, displacement for prismatic joints). We want to find the position and orientation of the end-effector (the “hand”) as a function of all joint variables:

T0n=f(q1,q2,,qn)T_0^n = f(q_1, q_2, \ldots, q_n)

where T0nT_0^n is the 4×4 homogeneous transformation matrix from the base frame {0}\{0\} to the end-effector frame {n}\{n\}.

The Kinematic Chain

The key insight is that we can break this problem into a chain of local transforms. Each link ii has a frame {i}\{i\} attached to it, and we need only describe how frame {i}\{i\} relates to frame {i1}\{i-1\}:

T0n=T01T12T23Tn1nT_0^n = T_0^1 \cdot T_1^2 \cdot T_2^3 \cdots T_{n-1}^n

Each Ti1iT_{i-1}^i is a 4×4 homogeneous transform that depends on the geometry of link ii and joint variable qiq_i. The overall transform is just a product of matrices — one per link.

Why This Works

Homogeneous transforms compose by multiplication (Module 3, Lesson 3). If TABT_A^B takes points from {B}\{B\} to {A}\{A\}, and TBCT_B^C takes points from {C}\{C\} to {B}\{B\}, then TAC=TABTBCT_A^C = T_A^B \cdot T_B^C takes points from {C}\{C\} all the way to {A}\{A\}. Forward kinematics is just this principle applied repeatedly along the chain.

Notation Convention

This module writes T0nT_0^n where the subscript is the reference frame and the superscript is the described frame: T0nT_0^n means “the pose of frame {n}\{n\} described in frame {0}\{0\}.” Module 4’s coordinate frames lesson placed them the other way: Tn0T_n^0 for the same transform (subscript = described, superscript = reference). Both conventions are common in robotics textbooks. The chain cancellation pattern here is T01T12=T02T_0^{\cancel{1}} \cdot T_{\cancel{1}}^2 = T_0^2 — adjacent superscript and subscript cancel. Always check which convention a textbook or library uses before combining transforms from different sources.

The Denavit-Hartenberg Convention

How do we parameterize each Ti1iT_{i-1}^i? We could use 6 parameters (3 for rotation, 3 for translation), but the Denavit-Hartenberg (DH) convention reduces this to just 4 parameters per link by placing coordinate frames according to specific rules.

DH Frame Assignment Rules

  1. The ziz_i axis lies along the axis of joint i+1i+1
  2. The xix_i axis points along the common normal from zi1z_{i-1} to ziz_i
  3. The yiy_i axis completes the right-handed frame

The Four DH Parameters

For each link ii, the transform Ti1iT_{i-1}^i is determined by four quantities:

ParameterSymbolDescription
Link lengthaia_iDistance between zi1z_{i-1} and ziz_i along xix_i
Link twistαi\alpha_iAngle from zi1z_{i-1} to ziz_i about xix_i
Link offsetdid_iDistance between xi1x_{i-1} and xix_i along zi1z_{i-1}
Joint angleθi\theta_iAngle from xi1x_{i-1} to xix_i about zi1z_{i-1}

For a revolute joint, θi\theta_i is the joint variable (qi=θiq_i = \theta_i) and the other three are constants determined by the robot’s geometry. For a prismatic joint, did_i is the joint variable.

The DH Transformation Matrix

The four parameters define the transform as a product of four elementary transforms:

Ti1i=Rotz(θi)Transz(di)Transx(ai)Rotx(αi)T_{i-1}^i = \text{Rot}_{z}(\theta_i) \cdot \text{Trans}_{z}(d_i) \cdot \text{Trans}_{x}(a_i) \cdot \text{Rot}_{x}(\alpha_i)

Multiplying these out gives a single 4×4 matrix:

Ti1i=[cosθisinθicosαisinθisinαiaicosθisinθicosθicosαicosθisinαiaisinθi0sinαicosαidi0001]T_{i-1}^i = \begin{bmatrix} \cos\theta_i & -\sin\theta_i\cos\alpha_i & \sin\theta_i\sin\alpha_i & a_i\cos\theta_i \\ \sin\theta_i & \cos\theta_i\cos\alpha_i & -\cos\theta_i\sin\alpha_i & a_i\sin\theta_i \\ 0 & \sin\alpha_i & \cos\alpha_i & d_i \\ 0 & 0 & 0 & 1 \end{bmatrix}

Standard vs. Modified DH

There are two DH conventions in common use: classical (Denavit & Hartenberg 1955) and modified (Craig, also called proximal). They differ in the order of the four elementary transforms and in how frames are placed. The formula above is the classical convention. Both are correct — just be consistent. When reading DH tables from a datasheet, check which convention is used.

The simplest nontrivial robot arm has two revolute joints in a plane. Let’s derive its forward kinematics step by step.

DH Parameters

Linkaia_iαi\alpha_idid_iθi\theta_i
1L1L_100θ1\theta_1
2L2L_200θ2\theta_2

Both joints are revolute, so θ1\theta_1 and θ2\theta_2 are the variables. Both link twists are zero because the joint axes are parallel (both perpendicular to the plane). Both offsets are zero because there’s no displacement along the zz axes.

For link 1 (α1=0,d1=0\alpha_1 = 0, d_1 = 0):

T01=[cosθ1sinθ10L1cosθ1sinθ1cosθ10L1sinθ100100001]T_0^1 = \begin{bmatrix} \cos\theta_1 & -\sin\theta_1 & 0 & L_1\cos\theta_1 \\ \sin\theta_1 & \cos\theta_1 & 0 & L_1\sin\theta_1 \\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 1 \end{bmatrix}

For link 2 (same structure):

T12=[cosθ2sinθ20L2cosθ2sinθ2cosθ20L2sinθ200100001]T_1^2 = \begin{bmatrix} \cos\theta_2 & -\sin\theta_2 & 0 & L_2\cos\theta_2 \\ \sin\theta_2 & \cos\theta_2 & 0 & L_2\sin\theta_2 \\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 1 \end{bmatrix}

Total Transform

T02=T01T12=[cos(θ1+θ2)sin(θ1+θ2)0L1cosθ1+L2cos(θ1+θ2)sin(θ1+θ2)cos(θ1+θ2)0L1sinθ1+L2sin(θ1+θ2)00100001]T_0^2 = T_0^1 \cdot T_1^2 = \begin{bmatrix} \cos(\theta_1+\theta_2) & -\sin(\theta_1+\theta_2) & 0 & L_1\cos\theta_1 + L_2\cos(\theta_1+\theta_2) \\ \sin(\theta_1+\theta_2) & \cos(\theta_1+\theta_2) & 0 & L_1\sin\theta_1 + L_2\sin(\theta_1+\theta_2) \\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 1 \end{bmatrix}

The end-effector position is read from the last column:

x=L1cosθ1+L2cos(θ1+θ2)x = L_1\cos\theta_1 + L_2\cos(\theta_1 + \theta_2) y=L1sinθ1+L2sin(θ1+θ2)y = L_1\sin\theta_1 + L_2\sin(\theta_1 + \theta_2)

and the orientation is θ1+θ2\theta_1 + \theta_2 (the upper-left 2×2 block is a rotation by this angle).

Numerical Verification Robotics Application

Let L1=2,L2=1.5,θ1=45°,θ2=60°L_1 = 2, L_2 = 1.5, \theta_1 = 45°, \theta_2 = 60°.

x=2cos(45°)+1.5cos(105°)2(0.707)+1.5(0.259)1.025x = 2\cos(45°) + 1.5\cos(105°) \approx 2(0.707) + 1.5(-0.259) \approx 1.025y=2sin(45°)+1.5sin(105°)2(0.707)+1.5(0.966)2.863y = 2\sin(45°) + 1.5\sin(105°) \approx 2(0.707) + 1.5(0.966) \approx 2.863

The end-effector is at approximately (1.03,2.86)(1.03, 2.86) with orientation 105°105°. You can verify this with the interactive visualization below.

Workspace

The workspace is the set of all points the end-effector can reach. For a 2-link planar arm:

When L1=L2L_1 = L_2, the inner boundary shrinks to a point and the robot can reach the origin (by folding completely back on itself).

Workspace vs. Configuration Space

The workspace lives in Cartesian coordinates (x, y for 2D; x, y, z for 3D). The configuration space (C-space) lives in joint coordinates (θ1,θ2,\theta_1, \theta_2, \ldots). Forward kinematics maps from C-space to workspace. Going the other direction — from a desired workspace position to the joint angles — is inverse kinematics, a harder problem that we don’t cover here.

Extension to 3D: The 6-DOF Arm

Real industrial robots typically have 6 revolute joints, giving 6 degrees of freedom — enough to independently control both position (3 DOF) and orientation (3 DOF) of the end-effector in 3D space.

PUMA 560 Robot Robotics Application

The classic PUMA 560 has the following DH parameters:

Linkaia_iαi\alpha_idid_iθi\theta_i
1090°-90°0θ1\theta_1
2a2a_200θ2\theta_2
3a3a_390°90°d3d_3θ3\theta_3
4090°-90°d4d_4θ4\theta_4
5090°90°0θ5\theta_5
600d6d_6θ6\theta_6

The forward kinematics is T06=T01T12T23T34T45T56T_0^6 = T_0^1 \cdot T_1^2 \cdot T_2^3 \cdot T_3^4 \cdot T_4^5 \cdot T_5^6 — six 4×4 matrix multiplications. The procedure is identical to the 2-link case, just with more links and nonzero twist angles αi\alpha_i.

Notice that links 4, 5, 6 have ai=0a_i = 0 and their αi\alpha_i values alternate between ±90°\pm 90°. These three joints form a spherical wrist — they intersect at a common point, which decouples position control (joints 1-3) from orientation control (joints 4-6).

The DH Transform in Code

The DH transform is already available in this project’s math library (src/lib/math/transforms.ts):

function dhTransform(a: number, alpha: number, d: number, theta: number): Matrix

For the 2-link arm, the forward kinematics is:

const T01 = dhTransform(L1, 0, 0, theta1);
const T12 = dhTransform(L2, 0, 0, theta2);
const T02 = multiply(T01, T12);  // End-effector transform

For an nn-link arm, just keep multiplying:

let T = identity(4);
for (let i = 0; i < n; i++) {
  const Ti = dhTransform(a[i], alpha[i], d[i], theta[i]);
  T = multiply(T, Ti);
}
// T is now T_0^n

Interactive Visualization

Adjust the joint angles and link lengths of a 2-link planar arm. The visualization computes forward kinematics using DH parameters and displays the resulting end-effector position, the full homogeneous transform T02T_0^2, and the coordinate frames at each joint.

Controls

Joint Angles

-3.1415926535897933.141592653589793
-3.1415926535897933.141592653589793

Link Lengths

0.53
0.53

End-Effector Position

x = 1.026
y = 2.863
orientation = 105.0°

T₀² (Base to End-Effector)

[-0.26-0.970.001.03]
[0.97-0.260.002.86]
[0.000.001.000.00]
[0.000.000.001.00]

Try this: Start at "Home" (both angles zero) to see the arm fully extended. Then adjust θ₂ to bend the elbow. Enable "Trace" and sweep θ₁ to see the end-effector trace an arc. Enable "Workspace" to see the full reachable region.

Practice Problems

  1. A 2-link planar arm has L1=3,L2=2L_1 = 3, L_2 = 2. Compute the end-effector position when θ1=30°,θ2=45°\theta_1 = 30°, \theta_2 = -45°.

  2. For the same arm, what is the maximum reach? What is the inner boundary radius?

  3. Write the DH table for a 3-link planar arm (three revolute joints in the same plane, link lengths L1,L2,L3L_1, L_2, L_3). What is T03T_0^3?

  4. A robot has DH parameters: link 1 with a1=0,α1=90°,d1=0.5,θ1a_1 = 0, \alpha_1 = 90°, d_1 = 0.5, \theta_1. Compute T01T_0^1 when θ1=0\theta_1 = 0.

  5. Why does a 6-DOF arm need exactly 6 joints to position and orient its end-effector arbitrarily in 3D space?

Answers
  1. x=3cos(30°)+2cos(30°45°)=3(0.866)+2(0.966)4.530x = 3\cos(30°) + 2\cos(30° - 45°) = 3(0.866) + 2(0.966) \approx 4.530. y=3sin(30°)+2sin(15°)=3(0.5)+2(0.259)0.982y = 3\sin(30°) + 2\sin(-15°) = 3(0.5) + 2(-0.259) \approx 0.982. End-effector is at approximately (4.53,0.98)(4.53, 0.98).

  2. Maximum reach = L1+L2=5L_1 + L_2 = 5 (arm fully extended). Inner boundary = L1L2=1|L_1 - L_2| = 1 (arm folded back).

  3. DH table adds a third row: link 3 with a3=L3,α3=0,d3=0,θ3a_3 = L_3, \alpha_3 = 0, d_3 = 0, \theta_3. The total transform T03=T01T12T23T_0^3 = T_0^1 \cdot T_1^2 \cdot T_2^3 gives end-effector position x=L1c1+L2c12+L3c123x = L_1 c_1 + L_2 c_{12} + L_3 c_{123}, y=L1s1+L2s12+L3s123y = L_1 s_1 + L_2 s_{12} + L_3 s_{123} where c12=cos(θ1+θ2)c_{12} = \cos(\theta_1 + \theta_2), etc.

  4. T01=[100000100100.50001]T_0^1 = \begin{bmatrix} 1 & 0 & 0 & 0 \\ 0 & 0 & -1 & 0 \\ 0 & 1 & 0 & 0.5 \\ 0 & 0 & 0 & 1 \end{bmatrix}. The z0z_0 axis maps to the y1y_1 axis (90° twist), and there’s a 0.5 offset along z0z_0.

  5. A rigid body in 3D has 6 degrees of freedom: 3 translational (x, y, z) and 3 rotational (roll, pitch, yaw). Each revolute joint contributes 1 DOF. So 6 joints give 6 DOF — just enough to independently control all 6 components. With fewer joints, some workspace directions are constrained. With more joints, the robot is redundant and has extra flexibility.

Key Takeaways

  1. Forward kinematics computes end-effector pose from joint variables: T0n=T01T12Tn1nT_0^n = T_0^1 \cdot T_1^2 \cdots T_{n-1}^n
  2. The DH convention parameterizes each link with 4 quantities: a,α,d,θa, \alpha, d, \theta
  3. Each link transform is a single 4×4 matrix; the chain is a matrix product
  4. The workspace is the reachable region in Cartesian space; the configuration space is the joint-angle space
  5. A 6-DOF arm can independently control position and orientation in 3D

Next Steps

Now that you can compute where the end-effector is, the next lesson addresses how fast it’s moving — the Jacobian and velocity kinematics.