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 joints. Each joint has a variable (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:
where is the 4×4 homogeneous transformation matrix from the base frame to the end-effector frame .
The Kinematic Chain
The key insight is that we can break this problem into a chain of local transforms. Each link has a frame attached to it, and we need only describe how frame relates to frame :
Each is a 4×4 homogeneous transform that depends on the geometry of link and joint variable . 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 takes points from to , and takes points from to , then takes points from all the way to . Forward kinematics is just this principle applied repeatedly along the chain.
Notation Convention
This module writes where the subscript is the reference frame and the superscript is the described frame: means “the pose of frame described in frame .” Module 4’s coordinate frames lesson placed them the other way: for the same transform (subscript = described, superscript = reference). Both conventions are common in robotics textbooks. The chain cancellation pattern here is — 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 ? 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
- The axis lies along the axis of joint
- The axis points along the common normal from to
- The axis completes the right-handed frame
The Four DH Parameters
For each link , the transform is determined by four quantities:
| Parameter | Symbol | Description |
|---|---|---|
| Link length | Distance between and along | |
| Link twist | Angle from to about | |
| Link offset | Distance between and along | |
| Joint angle | Angle from to about |
For a revolute joint, is the joint variable () and the other three are constants determined by the robot’s geometry. For a prismatic joint, is the joint variable.
The DH Transformation Matrix
The four parameters define the transform as a product of four elementary transforms:
Multiplying these out gives a single 4×4 matrix:
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.
Example: 2-Link Planar Arm
The simplest nontrivial robot arm has two revolute joints in a plane. Let’s derive its forward kinematics step by step.
DH Parameters
| Link | ||||
|---|---|---|---|---|
| 1 | 0 | 0 | ||
| 2 | 0 | 0 |
Both joints are revolute, so and 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 axes.
Link Transforms
For link 1 ():
For link 2 (same structure):
Total Transform
The end-effector position is read from the last column:
and the orientation is (the upper-left 2×2 block is a rotation by this angle).
Numerical Verification Robotics Application
Let .
The end-effector is at approximately with orientation . 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:
- Outer boundary: a circle of radius (arm fully extended)
- Inner boundary: a circle of radius (arm fully folded)
- The reachable workspace is the annular ring between these circles
When , 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 (). 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:
| Link | ||||
|---|---|---|---|---|
| 1 | 0 | 0 | ||
| 2 | 0 | 0 | ||
| 3 | ||||
| 4 | 0 | |||
| 5 | 0 | 0 | ||
| 6 | 0 | 0 |
The forward kinematics is — six 4×4 matrix multiplications. The procedure is identical to the 2-link case, just with more links and nonzero twist angles .
Notice that links 4, 5, 6 have and their values alternate between . 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 -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 , and the coordinate frames at each joint.
Joint Angles
Link Lengths
End-Effector Position
T₀² (Base to End-Effector)
| [ | -0.26 | -0.97 | 0.00 | 1.03 | ] |
| [ | 0.97 | -0.26 | 0.00 | 2.86 | ] |
| [ | 0.00 | 0.00 | 1.00 | 0.00 | ] |
| [ | 0.00 | 0.00 | 0.00 | 1.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
-
A 2-link planar arm has . Compute the end-effector position when .
-
For the same arm, what is the maximum reach? What is the inner boundary radius?
-
Write the DH table for a 3-link planar arm (three revolute joints in the same plane, link lengths ). What is ?
-
A robot has DH parameters: link 1 with . Compute when .
-
Why does a 6-DOF arm need exactly 6 joints to position and orient its end-effector arbitrarily in 3D space?
Answers
-
. . End-effector is at approximately .
-
Maximum reach = (arm fully extended). Inner boundary = (arm folded back).
-
DH table adds a third row: link 3 with . The total transform gives end-effector position , where , etc.
-
. The axis maps to the axis (90° twist), and there’s a 0.5 offset along .
-
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
- Forward kinematics computes end-effector pose from joint variables:
- The DH convention parameterizes each link with 4 quantities:
- Each link transform is a single 4×4 matrix; the chain is a matrix product
- The workspace is the reachable region in Cartesian space; the configuration space is the joint-angle space
- 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.