Configuration Spaces and Robot Geometry

Before reading this:

The configuration space is the single most important abstraction in motion planning. It lets us replace “a robot with intricate geometry avoiding intricate obstacles” with “a point moving in a higher-dimensional space where the obstacles are already baked in.” The cost of this abstraction is that the new space is topologically strange — it is almost never Rn\mathbb{R}^n. The reward is that every algorithm in the rest of this series operates on the abstracted version and is blissfully unaware of the underlying mechanical geometry. Introduced by Lozano-Pérez in 1983 [1], it is the bedrock the field is built on.

1. From workspace to configuration space

Let WRm\mathcal{W} \subseteq \mathbb{R}^m (with m{2,3}m \in \{2, 3\}) be the physical workspace the robot lives in. The robot is an articulated or rigid body occupying a subset A(q)W\mathcal{A}(q) \subseteq \mathcal{W} that depends on its joint vector qq. Obstacles are a subset OW\mathcal{O} \subseteq \mathcal{W}.

Definition — configuration space

The configuration space C\mathcal{C} of a robot is the set of all configurations qq — i.e., the set of parameter vectors that completely determine the robot’s pose in the workspace. The free space is

Cfree={qCA(q)O= and A(q) is self-collision-free}\mathcal{C}_{\text{free}} = \{q \in \mathcal{C} \mid \mathcal{A}(q) \cap \mathcal{O} = \emptyset \text{ and } \mathcal{A}(q) \text{ is self-collision-free}\}

and the obstacle region is Cobs=CCfree\mathcal{C}_{\text{obs}} = \mathcal{C} \setminus \mathcal{C}_{\text{free}}.

The key observation is that collision detection in the workspace becomes containment in the configuration space: we no longer ask “do these polygons intersect?” but instead “is this point inside this (weird) region?”

The planning problem restated. Given qs,qgCfreeq_s, q_g \in \mathcal{C}_{\text{free}}, find a continuous function

τ:[0,1]Cfree,τ(0)=qs,τ(1)=qg.\tau : [0,1] \to \mathcal{C}_{\text{free}}, \qquad \tau(0) = q_s, \quad \tau(1) = q_g.

Existence of such a τ\tau reduces exactly to qsq_s and qgq_g lying in the same path-connected component of Cfree\mathcal{C}_{\text{free}} — a purely topological statement. This is why topology matters so much for planning.

2. Counting degrees of freedom

A degree of freedom (DoF) is an independent parameter needed to specify the pose. For an open kinematic chain, Grübler’s formula gives

DoF=6ni=1J(6fi)\text{DoF} = 6n - \sum_{i=1}^J (6 - f_i)

for a spatial mechanism with nn moving bodies and JJ joints, where fif_i is the number of DoF of joint ii (1 for revolute/prismatic, 2 for universal, 3 for spherical). For an open chain with all 1-DoF joints this collapses to DoF=n\text{DoF} = n.

RobotDoFC-spaceTopology
Point in plane2R2\mathbb{R}^2Euclidean
Point in 3D3R3\mathbb{R}^3Euclidean
Rigid body in plane3SE(2)=R2×S1SE(2) = \mathbb{R}^2 \times S^1Cylinder
Rigid body in 3D6SE(3)=R3SO(3)SE(3) = \mathbb{R}^3 \rtimes SO(3)R3×RP3\mathbb{R}^3 \times \mathbb{RP}^3
nn-revolute planar armnnTn\mathbb{T}^nnn-torus
Franka Panda arm7T7\mathbb{T}^7 (with joint limits)open subset of R7\mathbb{R}^7
Quadruped with floating base18SE(3)×T12SE(3) \times \mathbb{T}^{12}product manifold
Humanoid (e.g. Atlas)30+SE(3)×TnjSE(3) \times \mathbb{T}^{n_j}product manifold

Observe how quickly dimensions grow. A humanoid’s 30-D C\mathcal{C} contains 1030\sim 10^{30} cells even at a crude 10-per-dimension grid — already beyond brute force. This is why all modern planners sample or optimise rather than enumerate.

3. The manifolds you will actually meet

3.1 Euclidean space Rn\mathbb{R}^n

Prismatic joints and free-floating point robots give a true Euclidean C\mathcal{C}. Distances are Euclidean, interpolation is linear, everything is easy. Almost nothing in robotics lives here exclusively.

3.2 The circle S1S^1 and the torus Tn\mathbb{T}^n

A single revolute joint has configuration space S1S^1: angles θ\theta and θ+2π\theta + 2\pi are the same physical point. The right distance is the wrapped angular distance:

dS1(θ1,θ2)=min(θ1θ2, 2πθ1θ2).d_{S^1}(\theta_1, \theta_2) = \min(|\theta_1 - \theta_2|,\ 2\pi - |\theta_1 - \theta_2|).

Equivalently, viewing S1R2S^1 \hookrightarrow \mathbb{R}^2 via θ(cosθ,sinθ)\theta \mapsto (\cos\theta, \sin\theta), the chord distance 2sin(d/2)2\sin(d/2) is monotone in dd, so using Euclidean distance on the embedded circle is fine — an important trick for nearest-neighbour searches.

An nn-joint all-revolute arm has C=Tn\mathcal{C} = \mathbb{T}^n, the nn-torus. Its topology is fundamentally non-Euclidean: there exist loops that cannot be continuously shrunk to a point. This matters because a shortest path on the torus may wrap around.

Wraparound bugs are the first real bug you will write

It is tempting to treat angular joints as if they live in R\mathbb{R}. This produces planners that take the scenic route (3π/23\pi/2 radians CCW instead of π/2\pi/2 CW) and, worse, nearest-neighbour structures that are silently wrong. Always pick a metric that matches the topology of your space.

3.3 SE(2)SE(2): planar rigid bodies

A rigid body in the plane has C=R2×S1\mathcal{C} = \mathbb{R}^2 \times S^1, parameterised as (x,y,θ)(x, y, \theta). It is a group under composition:

(x1,y1,θ1)(x2,y2,θ2)=(x1+cosθ1x2sinθ1y2, y1+sinθ1x2+cosθ1y2, θ1+θ2).(x_1, y_1, \theta_1) \cdot (x_2, y_2, \theta_2) = \left(x_1 + \cos\theta_1\, x_2 - \sin\theta_1\, y_2,\ y_1 + \sin\theta_1\, x_2 + \cos\theta_1\, y_2,\ \theta_1 + \theta_2\right).

A natural metric is the weighted Euclidean distance

dSE(2)((x1,y1,θ1),(x2,y2,θ2))=(x1x2)2+(y1y2)2+w2dS1(θ1,θ2)2d_{SE(2)}((x_1,y_1,\theta_1), (x_2,y_2,\theta_2)) = \sqrt{(x_1-x_2)^2 + (y_1-y_2)^2 + w^2 d_{S^1}(\theta_1,\theta_2)^2}

where ww is a user-chosen weight balancing angular and translational “importance.” There is no principled universal choice of ww — it depends on how far the robot tends to translate vs. rotate per plan. Picking ww badly makes sampling-based planners silently wrong (by deforming which neighbours look close).

3.4 SO(3)SO(3) and SE(3)SE(3): 3D orientations and rigid bodies

Rotations in 3D form the group

SO(3)={RR3×3RR=I, detR=1}.SO(3) = \{R \in \mathbb{R}^{3\times 3} \mid R^\top R = I,\ \det R = 1\}.

This is a 3-dimensional Lie group — a smooth manifold that is also a group. Several coordinatisations exist, each with pathologies:

The unit quaternion representation is almost universally the right choice in a motion planner. Interpolation between two orientations uses spherical linear interpolation (SLERP) [2]:

SLERP(q1,q2,t)=sin((1t)Ω)sinΩq1+sin(tΩ)sinΩq2,cosΩ=q1q2.\text{SLERP}(q_1, q_2, t) = \frac{\sin((1-t)\Omega)}{\sin\Omega} q_1 + \frac{\sin(t\Omega)}{\sin\Omega} q_2,\qquad \cos\Omega = q_1 \cdot q_2.

Bi-invariant distance on SO(3)SO(3):

dSO(3)(R1,R2)=log(R1R2)F/2=arccos ⁣(tr(R1R2)12).d_{SO(3)}(R_1, R_2) = \|\log(R_1^\top R_2)\|_F / \sqrt 2 = \arccos\!\left(\frac{\mathrm{tr}(R_1^\top R_2) - 1}{2}\right).

This is the angle of the smallest rotation that takes R1R_1 to R2R_2, and is the only metric that respects the symmetry of the group.

SE(3)=R3SO(3)SE(3) = \mathbb{R}^3 \rtimes SO(3) adds translation. A common practical metric is weighted Euclidean on position plus a weighted bi-invariant angle, with the usual caveat about weight selection.

Compare Euler-angle linear interpolation with SLERP on the same start and end orientation. The Euler path wobbles and can gimbal-lock; SLERP traces a constant-angular-velocity rotation about a single fixed axis.

For the full Lie-group machinery of SE(3)SE(3) — exponential maps, twists, adjoint representations — see the dedicated Lie groups note or [3] Chapter 3. In this series we use enough of it to make sampling, interpolation, and distances work; we do not derive the machinery from scratch.

4. Computing C-space obstacles: the Minkowski sum

For a translating-only rigid body ARm\mathcal{A} \subset \mathbb{R}^m among obstacles BRm\mathcal{B} \subset \mathbb{R}^m, the C-obstacle is

Cobs=B(A)={babB, aA},\mathcal{C}_{\text{obs}} = \mathcal{B} \oplus (-\mathcal{A}) = \{\mathbf{b} - \mathbf{a} \mid \mathbf{b} \in \mathcal{B},\ \mathbf{a} \in \mathcal{A}\},

where \oplus denotes the Minkowski sum. The intuition: qCobsq \in \mathcal{C}_{\text{obs}} iff there exists aA\mathbf{a} \in \mathcal{A} with q+aBq + \mathbf{a} \in \mathcal{B}, i.e. iff some point of the robot (translated to qq) is inside an obstacle point.

4.1 Why it works

Let A(q)=q+A0\mathcal{A}(q) = q + \mathcal{A}_0 be the robot placed at configuration qq, where A0\mathcal{A}_0 is the robot in its reference pose. Then

A(q)B    aA0:q+aB    qB+(A0)=B(A0).\mathcal{A}(q) \cap \mathcal{B} \neq \emptyset \iff \exists \mathbf{a} \in \mathcal{A}_0: q + \mathbf{a} \in \mathcal{B} \iff q \in \mathcal{B} + (-\mathcal{A}_0) = \mathcal{B} \oplus (-\mathcal{A}_0).

So the obstacle in C\mathcal{C} is literally the obstacle in workspace, inflated by the reflected robot.

4.2 Convex Minkowski sums via rotating calipers

For convex polygons, the Minkowski sum is convex and has at most A+B|\mathcal{A}| + |\mathcal{B}| vertices. A classical linear-time algorithm uses rotating calipers: list the edges of both polygons in CCW order by angle; walk the merged list, outputting sums of corresponding vertices.

minkowski_sum.py
import numpy as np
 
def minkowski_sum(poly_a, poly_b):
    """Minkowski sum of two CCW-ordered convex polygons.
 
    Both inputs are lists of (x, y) vertices in CCW order with the
    smallest (y, x) vertex first. Returns the sum polygon in CCW order.
    Runs in O(|A| + |B|).
    """
    def edges(p):
        return [np.array(p[(i+1) % len(p)]) - np.array(p[i])
                for i in range(len(p))]
 
    ea, eb = edges(poly_a), edges(poly_b)
    i = j = 0
    result = []
    base = np.array(poly_a[0]) + np.array(poly_b[0])
    result.append(base.tolist())
 
    while i < len(ea) or j < len(eb):
        if j == len(eb) or (i < len(ea) and np.cross(ea[i], eb[j]) >= 0):
            base = base + ea[i]; i += 1
        else:
            base = base + eb[j]; j += 1
        result.append(base.tolist())
 
    return result[:-1]  # last point coincides with first

Edit the two polygons directly — drag vertices, add or remove them, or drag whole shapes. The green outline is ABA \oplus B; toggle Reflect A to see the C-obstacle interpretation B(A)B \oplus (-A).

4.3 What happens when the robot can rotate

For a rigid body that both translates and rotates, C=SE(2)\mathcal{C} = SE(2) or SE(3)SE(3), and Cobs\mathcal{C}_{\text{obs}} is a 3- or 6-dimensional region that can be constructed as a stack of translation-only Minkowski sums, one per orientation:

Cobs=θS1{θ}×(B(RθA0)).\mathcal{C}_{\text{obs}} = \bigcup_{\theta \in S^1}\{\theta\} \times \big(\mathcal{B} \oplus (-R_\theta \mathcal{A}_0)\big).

The slices for different θ\theta are different shapes. Critically, the union is almost never convex even if A0\mathcal{A}_0 and B\mathcal{B} are: rotating the robot changes which edge is closest to the obstacle, producing non-convex “swept” regions with curved boundaries. This is already enough to kill naive approaches.

4.4 Why we abandon explicit computation in high dimensions

For an nn-joint revolute arm, Cobs\mathcal{C}_{\text{obs}} is an nn-dimensional region with no closed-form description. Canny [4] gave a singly-exponential (O(npolylog)O(n^{\text{polylog}})) algorithm for explicit computation under strong assumptions, but in practice — for n3n \ge 3 — we give up entirely on representing Cobs\mathcal{C}_{\text{obs}} and instead provide an oracle: a function that tells us, for any qq, whether qCfreeq \in \mathcal{C}_{\text{free}}. This is the job of the collision checker and the reason it dominates planning wall-clock time.

5. Metrics, interpolation, and sampling

Because motion planners will need to (a) measure distance, (b) interpolate between two configurations, and (c) sample configurations from C\mathcal{C}, every C-space needs equipping with three operations:

5.1 Distance

A metric d:C×CR0d: \mathcal{C} \times \mathcal{C} \to \mathbb{R}_{\ge 0} with d(q1,q2)=0    q1=q2d(q_1,q_2) = 0 \iff q_1 = q_2, symmetry, and the triangle inequality. The “right” metric depends on the manifold:

5.2 Interpolation

Given two configurations q1,q2q_1, q_2 and t[0,1]t \in [0,1], produce q(t)Cq(t) \in \mathcal{C} such that q(0)=q1q(0) = q_1, q(1)=q2q(1) = q_2. Interpolation must track the geodesic:

5.3 Sampling

Random sampling from C\mathcal{C} is a prerequisite for PRM and RRT. “Uniform” is subtle:

uniform_so3.py
import numpy as np
 
def uniform_quaternion():
    """Uniform sample on S^3 (equivalently SO(3) up to antipodal)."""
    u1, u2, u3 = np.random.random(3)
    q = np.array([
        np.sqrt(1 - u1) * np.sin(2*np.pi*u2),
        np.sqrt(1 - u1) * np.cos(2*np.pi*u2),
        np.sqrt(u1)     * np.sin(2*np.pi*u3),
        np.sqrt(u1)     * np.cos(2*np.pi*u3),
    ])
    return q

This is Shoemake’s 1992 subgroup algorithm; see [5] §5.2 for the derivation from Haar measure on SO(3)SO(3).

6. Worked example: the planar 2R arm

The 2R planar arm — two rigid links of lengths 1,2\ell_1, \ell_2 connected by two revolute joints — is the canonical “toy that is not too toy” for C-space intuition. Its forward kinematics are

x(θ1,θ2)=1cosθ1+2cos(θ1+θ2),x(\theta_1, \theta_2) = \ell_1 \cos\theta_1 + \ell_2 \cos(\theta_1 + \theta_2), y(θ1,θ2)=1sinθ1+2sin(θ1+θ2).y(\theta_1, \theta_2) = \ell_1 \sin\theta_1 + \ell_2 \sin(\theta_1 + \theta_2).

Its C-space is T2\mathbb{T}^2: both angles are periodic. Unroll T2\mathbb{T}^2 into the unit square [0,2π)2[0, 2\pi)^2 with identified edges; the resulting picture is the standard “torus as square” diagram.

Computing Cobs\mathcal{C}_{\text{obs}} numerically. There is no closed form. We grid T2\mathbb{T}^2 at some resolution, run forward kinematics at each grid point, test for collision between the link geometry and the workspace obstacles, and mark collisions. With a 200×200 grid that’s 40,000 collision checks; perfectly tractable.

2r_arm_cobs.py
import numpy as np
 
def arm_segments(theta1, theta2, L1=1.0, L2=1.0):
    """Return the two link segments as ((x0,y0),(x1,y1))."""
    x1 = L1*np.cos(theta1); y1 = L1*np.sin(theta1)
    x2 = x1 + L2*np.cos(theta1 + theta2); y2 = y1 + L2*np.sin(theta1 + theta2)
    return ((0.0, 0.0), (x1, y1)), ((x1, y1), (x2, y2))
 
def segment_intersects_circle(p0, p1, center, radius):
    """Closest-point test: segment vs. circular obstacle."""
    d = np.array(p1) - np.array(p0); f = np.array(p0) - np.array(center)
    a = d @ d; b = 2*(f @ d); c = f @ f - radius**2
    disc = b*b - 4*a*c
    if disc < 0: return False
    disc = np.sqrt(disc); t1 = (-b - disc)/(2*a); t2 = (-b + disc)/(2*a)
    return (0 <= t1 <= 1) or (0 <= t2 <= 1) or (t1 < 0 and t2 > 1)
 
def c_obstacle_grid(obstacles, resolution=200):
    """Returns a boolean grid where True = collision."""
    grid = np.zeros((resolution, resolution), dtype=bool)
    thetas = np.linspace(0, 2*np.pi, resolution, endpoint=False)
    for i, t1 in enumerate(thetas):
        for j, t2 in enumerate(thetas):
            s1, s2 = arm_segments(t1, t2)
            for (cx, cy, r) in obstacles:
                if segment_intersects_circle(*s1, (cx,cy), r) or \
                   segment_intersects_circle(*s2, (cx,cy), r):
                    grid[i, j] = True; break
    return grid

If you run this with a single circular obstacle near the workspace origin, Cobs\mathcal{C}_{\text{obs}} looks like a pair of twisted bands on the torus — nothing like the circular shape in workspace, and visibly wrapping around. This is the picture everyone must see at least once.

Left: the 2R arm in workspace. Right: its configuration space as the unit square [0,2π)2[0,2\pi)^2, with edges identified. Drag the obstacle in workspace and watch one round shape become a pair of twisted bands in C-space; click anywhere in the right panel to teleport the arm to that configuration.

7. Topology bites back

Consider two configurations qs=(0.1,0.0)q_s = (0.1, 0.0) and qg=(2π0.1,0.0)q_g = (2\pi - 0.1, 0.0) in T2\mathbb{T}^2. In the unwrapped square they look far apart — Euclidean distance 2π0.26.08\approx 2\pi - 0.2 \approx 6.08. In the torus, they are close: the short path goes through the identification θ1=02π\theta_1 = 0 \equiv 2\pi, and the geodesic distance is only 0.20.2.

The unrolled torus on the left, the true T2\mathbb{T}^2 on the right. The dashed orange segment is the naive Euclidean straight line in the unwrapped square — wrong. The green curve is the actual geodesic, which may leave one edge and re-enter on the other. Drag either endpoint to explore.

Your nearest-neighbour data structure must know the topology

Standard kk-d trees and ball trees assume a Euclidean metric. For toroidal dimensions you must either wrap the coordinates explicitly, embed into (cos,sin)(\cos, \sin) doubles (doubling memory but straightforward), or use a library that supports non-Euclidean metrics (e.g. OMPL’s GNAT). Getting this wrong produces plans that silently waste half the configuration space.

Topology affects more than distance:

8. The complexity of motion planning

Reif [6] proved, already in 1979, that the general motion planning problem — deciding whether a piecewise-linear dd-DoF robot can reach a goal among polyhedral obstacles — is PSPACE-hard in dd. Canny [4] later gave a singly-exponential algorithm, matching the complexity lower bound: the general problem is inherently exponential in the dimension.

Theorem — Canny, 1988

The generalised mover’s problem for a dd-DoF robot in R3\mathbb{R}^3 with nn algebraic-surface obstacle facets can be solved in time nO(1)2O(d)n^{O(1)} 2^{O(d)} [4].

Combined with Reif’s hardness result, this tells us that the dependence on dimension is essentially optimal in the worst case. Low-dimensional cases admit much better algorithms:

SettingComplexity
2D translation, polygonal obstaclesO(nlogn)O(n \log n) (visibility graphs)
2D translation + rotationPSPACE-hard in general
3D translation, convex obstaclespolynomial
3D rigid body, polyhedralsingly exponential
dd-DoF generalPSPACE-complete

The practical consequences of this hardness are everywhere. We cannot compute Cobs\mathcal{C}_{\text{obs}} explicitly; we cannot enumerate its connected components; we cannot even decide reachability optimally. Every practical planner is an approximation: grid discretisation (resolution completeness), random sampling (probabilistic completeness), or gradient-based local search (no completeness, but fast). The rest of the series is essentially a tour of how each approximation copes with this unavoidable hardness.

References

  1. 1.
  2. 2.
  3. 3.
  4. 4.
  5. 5.
  6. 6.
Cite this note
@online{zandonati2026configuration,
  author    = {Ben Zandonati},
  title     = {Configuration Spaces and Robot Geometry},
  year      = {2026},
  month     = {apr},
  url       = {https://benzandonati.co.uk/notes/mp_notes/mp-01-configuration-space/},
  urldate   = {2026-05-10},
  note      = {Online; accessed 2026-05-10},
  keywords  = {motion-planning, robotics, c-space, geometry, topology, lie-groups},
}

Ben Zandonati (2026). Configuration Spaces and Robot Geometry. Retrieved from https://benzandonati.co.uk/notes/mp_notes/mp-01-configuration-space/

Suggest an edit