RobotForge
Published·~13 min

Denavit-Hartenberg parameters (and why we're moving past them)

DH was the standard arm-kinematics formulation for 50 years. It still shows up in textbooks and FK code. Here's how it works, why it survives, and what modern textbooks (and URDFs) prefer.

by RobotForge
#kinematics#dh#arm

If you read any pre-2015 robotics paper on arm kinematics, you'll meet Denavit-Hartenberg parameters within three pages. The notation is compact: four numbers per joint and you can describe any serial chain. Then URDF arrived, software ate hardware, and DH started fading. Here's the working knowledge — enough to read the canon, and enough to know why modern code uses something different.

The four DH parameters

For each joint i, DH defines four numbers that relate frame i-1 to frame i:

  • — link length (along )
  • — link twist (rotation around )
  • — link offset (along )
  • — joint angle (rotation around )

For revolute joints, is the variable; for prismatic, is. The other three are fixed by the mechanism's geometry.

The transformation

The 4×4 homogeneous transform from frame i-1 to frame i is the product of four elementary motions:

Multiply out:

For a 6-DOF arm, multiply six of these together: forward kinematics. Substitute joint variables and you have the end-effector pose.

The convention question

Two slightly different DH conventions exist, and they bite people:

  • Standard DH (Denavit & Hartenberg 1955): the transformation above. Frame is attached to the distal end of link .
  • Modified DH (Craig, 1986): frame is at the proximal end. Different transform formula.

Both are used. Industrial datasheets are split. If you copy DH parameters from one source and plug into a library expecting the other, your forward kinematics will be silently wrong. Always check which convention.

A concrete example: 2-link planar arm

For a 2-link arm (shoulder + elbow), both joints are revolute, no offsets, links of length and :

i a α d θ
100
200

Plug into the formula, multiply, get the same we derived in the FK lesson. DH gave the same answer with more setup.

The payoff: the same DH machinery works for any serial chain. A 6-DOF Stäubli, a 7-DOF Sawyer — fill in the table, multiply.

Why textbooks still teach it

Three reasons:

  • Compact: 4 numbers per joint instead of a full 4×4 matrix.
  • Tied to standard solvers: many analytical IK solvers (IKFast, etc.) ingest DH. Industrial robot manuals quote DH.
  • Covered in every classical textbook: Spong, Craig, Sciavicco. If you're reading the literature, you need to read DH.

Why modern codebases don't

  • URDF is more general: lets you describe joints with arbitrary axes, offsets, and visual meshes. DH limits you to the canonical four parameters per joint.
  • The two conventions create silent bugs: standard vs modified DH parameter tables aren't interchangeable.
  • Visual debugging is harder: DH frames don't always coincide with physical features (joint axes are constrained to specific positions).
  • PoE (Product of Exponentials) uses screws and is conceptually cleaner — see the next lesson.

When you'll actually meet DH in 2026

  • Industrial-arm datasheets: KUKA, Stäubli, ABB still publish DH parameters in technical specs.
  • Legacy IK solvers: ROS-Industrial moveit_resources publishes DH-derived solver tables.
  • Textbooks: Modern Robotics (Lynch & Park) uses PoE; Craig and Spong use DH. You'll read both.
  • Quick FK from a manufacturer-supplied table: when all you have is the DH table, computing FK is fastest by punching the parameters into a library.

The Python recipe

import numpy as np

def dh_transform(a, alpha, d, theta):
    ca, sa = np.cos(alpha), np.sin(alpha)
    ct, st = np.cos(theta), np.sin(theta)
    return np.array([
        [ct, -st * ca,  st * sa, a * ct],
        [st,  ct * ca, -ct * sa, a * st],
        [0,        sa,       ca,      d],
        [0,         0,        0,      1],
    ])

# 6-DOF arm DH table (Standard DH)
dh = [
    # a, alpha, d, theta
    [0,    np.pi/2, 0.333, 0],
    [0,         0, 0,     0],
    # ... fill in for each joint
]

def forward_kinematics(joint_angles):
    T = np.eye(4)
    for (a, alpha, d, _), theta in zip(dh, joint_angles):
        T = T @ dh_transform(a, alpha, d, theta)
    return T

Twenty lines for FK on any DH-described chain. Plug in the manufacturer's table; compute the end-effector pose.

The IK story

For specific arm geometries (6-DOF spherical wrist), DH-based analytical IK exists and runs in microseconds. IKFast generates these solvers from DH tables — still the production-grade IK for many industrial arms. Worth knowing for 6-DOF UR / Franka / Kuka users.

Common pitfalls

  • Mixed conventions in a project — half the team uses standard DH, half uses modified. Pick one and document.
  • Sign of α — flipping it inverts the joint axis silently.
  • Initial offset — many real arms have a physical zero offset; the "θ = 0" in DH may not be the home position your driver thinks. Add a per-joint offset on top.
  • DH from CAD — extracting DH from a CAD model is tedious and error-prone. Easier to write a URDF and let tf2_kdl compute kinematics for you.

What to do if you're starting today

Don't build a new project on DH. Use URDF (descriptive, visual, integrates with ROS) or Modern Robotics' Product of Exponentials (cleaner math). Read DH only when you have to — for an old paper or an industrial datasheet.

Exercise

Find the DH table of a 6-DOF arm (Universal Robots, Franka — both publish theirs). Implement dh_transform above. Compute forward kinematics for a few joint configurations and compare against the official URDF (using tf2_kdl or PyKDL). Watch the answers agree. You've now bridged classical kinematics notation and modern URDF-based tools — useful when reading any ten-year-old paper on arm control.

Next

Inverse kinematics with iterative (Jacobian-based) methods — the only IK approach that works on 7+ DOF arms.

Comments

    Sign in to post a comment.