Configuration Spaces and Robot Geometry
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 . 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 (with ) be the physical workspace the robot lives in. The robot is an articulated or rigid body occupying a subset that depends on its joint vector . Obstacles are a subset .
The configuration space of a robot is the set of all configurations — i.e., the set of parameter vectors that completely determine the robot’s pose in the workspace. The free space is
and the obstacle region is .
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 , find a continuous function
Existence of such a reduces exactly to and lying in the same path-connected component of — 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
for a spatial mechanism with moving bodies and joints, where is the number of DoF of joint (1 for revolute/prismatic, 2 for universal, 3 for spherical). For an open chain with all 1-DoF joints this collapses to .
| Robot | DoF | C-space | Topology |
|---|---|---|---|
| Point in plane | 2 | Euclidean | |
| Point in 3D | 3 | Euclidean | |
| Rigid body in plane | 3 | Cylinder | |
| Rigid body in 3D | 6 | ||
| -revolute planar arm | -torus | ||
| Franka Panda arm | 7 | (with joint limits) | open subset of |
| Quadruped with floating base | 18 | product manifold | |
| Humanoid (e.g. Atlas) | 30+ | product manifold |
Observe how quickly dimensions grow. A humanoid’s 30-D contains 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
Prismatic joints and free-floating point robots give a true Euclidean . Distances are Euclidean, interpolation is linear, everything is easy. Almost nothing in robotics lives here exclusively.
3.2 The circle and the torus
A single revolute joint has configuration space : angles and are the same physical point. The right distance is the wrapped angular distance:
Equivalently, viewing via , the chord distance is monotone in , so using Euclidean distance on the embedded circle is fine — an important trick for nearest-neighbour searches.
An -joint all-revolute arm has , the -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.
It is tempting to treat angular joints as if they live in . This produces planners that take the scenic route ( radians CCW instead of CW) and, worse, nearest-neighbour structures that are silently wrong. Always pick a metric that matches the topology of your space.
3.3 : planar rigid bodies
A rigid body in the plane has , parameterised as . It is a group under composition:
A natural metric is the weighted Euclidean distance
where is a user-chosen weight balancing angular and translational “importance.” There is no principled universal choice of — it depends on how far the robot tends to translate vs. rotate per plan. Picking badly makes sampling-based planners silently wrong (by deforming which neighbours look close).
3.4 and : 3D orientations and rigid bodies
Rotations in 3D form the group
This is a 3-dimensional Lie group — a smooth manifold that is also a group. Several coordinatisations exist, each with pathologies:
- Euler angles (roll, pitch, yaw): 3 parameters but singular (gimbal lock); two rotation axes align and you lose a DoF.
- Axis-angle : 3 parameters (packed as ); not unique at or .
- Rotation matrices: 9 parameters with 6 constraints — no singularities, but inflated.
- Unit quaternions : 4 parameters with one constraint ; no singularities, but and represent the same rotation, so the underlying manifold is the real projective space .
The unit quaternion representation is almost universally the right choice in a motion planner. Interpolation between two orientations uses spherical linear interpolation (SLERP) [2]:
Bi-invariant distance on :
This is the angle of the smallest rotation that takes to , and is the only metric that respects the symmetry of the group.
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 — 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 among obstacles , the C-obstacle is
where denotes the Minkowski sum. The intuition: iff there exists with , i.e. iff some point of the robot (translated to ) is inside an obstacle point.
4.1 Why it works
Let be the robot placed at configuration , where is the robot in its reference pose. Then
So the obstacle in 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 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.
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 firstEdit the two polygons directly — drag vertices, add or remove them, or drag whole shapes. The green outline is ; toggle Reflect A to see the C-obstacle interpretation .
4.3 What happens when the robot can rotate
For a rigid body that both translates and rotates, or , and is a 3- or 6-dimensional region that can be constructed as a stack of translation-only Minkowski sums, one per orientation:
The slices for different are different shapes. Critically, the union is almost never convex even if and 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 -joint revolute arm, is an -dimensional region with no closed-form description. Canny [4] gave a singly-exponential () algorithm for explicit computation under strong assumptions, but in practice — for — we give up entirely on representing and instead provide an oracle: a function that tells us, for any , whether . 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 , every C-space needs equipping with three operations:
5.1 Distance
A metric with , symmetry, and the triangle inequality. The “right” metric depends on the manifold:
- : Euclidean, optionally weighted.
- : wrapped angular.
- : sum of wrapped angular distances per joint, or Euclidean distance on the embedded coordinates.
- : arccos trace formula above, or geodesic on the unit quaternion sphere (equivalent up to a factor of 2).
- : weighted combination; no canonical choice.
5.2 Interpolation
Given two configurations and , produce such that , . Interpolation must track the geodesic:
- : linear.
- : linear in the wrapped sense (go the short way).
- : SLERP on quaternions.
- : linear translation + SLERP rotation (practical), or exact screw motion via Lie-algebra exponentials (principled; see the dedicated Lie groups note).
5.3 Sampling
Random sampling from is a prerequisite for PRM and RRT. “Uniform” is subtle:
- : hypercube rejection.
- : uniform per angle.
- : uniformly sampling Euler angles is biased! The right method samples unit quaternions uniformly on (e.g. using three standard normals normalised to unit length, or the Shoemake subgroup algorithm).
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 qThis is Shoemake’s 1992 subgroup algorithm; see [5] §5.2 for the derivation from Haar measure on .
6. Worked example: the planar 2R arm
The 2R planar arm — two rigid links of lengths connected by two revolute joints — is the canonical “toy that is not too toy” for C-space intuition. Its forward kinematics are
Its C-space is : both angles are periodic. Unroll into the unit square with identified edges; the resulting picture is the standard “torus as square” diagram.
Computing numerically. There is no closed form. We grid 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.
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 gridIf you run this with a single circular obstacle near the workspace origin, 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 , 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 and in . In the unwrapped square they look far apart — Euclidean distance . In the torus, they are close: the short path goes through the identification , and the geodesic distance is only .
The unrolled torus on the left, the true 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.
Standard -d trees and ball trees assume a Euclidean metric. For toroidal dimensions you must either wrap the coordinates explicitly, embed into 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:
- Homotopy classes. Two paths can be in the same path-connected component but not homotopic — you can’t deform one into the other. Planning the “other side” of an obstacle in a multiply-connected space is a different homotopy class. This matters for multi-robot coordination and for human-like motion.
- Contractibility. is contractible; is not; is not (its fundamental group is ). These facts occasionally matter for proving convergence properties of global planners.
- Dimensionality curse. for a humanoid has volume whose unit-ball fraction scales like . In dimensions, the unit ball occupies essentially zero fraction of the unit cube. Any naive volume-based argument collapses.
8. The complexity of motion planning
Reif [6] proved, already in 1979, that the general motion planning problem — deciding whether a piecewise-linear -DoF robot can reach a goal among polyhedral obstacles — is PSPACE-hard in . Canny [4] later gave a singly-exponential algorithm, matching the complexity lower bound: the general problem is inherently exponential in the dimension.
The generalised mover’s problem for a -DoF robot in with algebraic-surface obstacle facets can be solved in time [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:
| Setting | Complexity |
|---|---|
| 2D translation, polygonal obstacles | (visibility graphs) |
| 2D translation + rotation | PSPACE-hard in general |
| 3D translation, convex obstacles | polynomial |
| 3D rigid body, polyhedral | singly exponential |
| -DoF general | PSPACE-complete |
The practical consequences of this hardness are everywhere. We cannot compute 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.
- 2.
- 3.
- 4.
- 5.
- 6.
@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/