Interactive Inverse Kinematics: CCD, FABRIK, and Jacobian Transpose
Inverse kinematics (IK) asks: given a desired end‑effector position, what joint angles produce it? Below you can compare three widely used IK solvers side‑by‑side on a planar arm. Drag the target, switch algorithms, and tune parameters to feel their behavior.
Algorithm Selection
Basic Parameters
Algorithm Settings
Joint Limits
Rest Pose
Moving Target
Visualization & Utilities
Status
Tips
- Drag anywhere to move the target; hold Shift to move the base.
- CCD: simple and robust; converges gradually joint‑by‑joint.
- FABRIK: geometric, fast convergence in many cases.
- Jacobian‑Transpose: gradient‑like; tune γ for stability.
IK Playground Help
Drag to move the target; hold Shift to drag the base. Use the controls to change solver, link count/length, iterations, damping, joint limits, and add a rest‑pose bias.
Moving targets let you compare tracking behavior.
- Shortcuts: 1=CCD, 2=FABRIK, 3=JT, 4=DLS, p=pause, t=trace, g=reach, k=metrics, ?=help, c=circle, l=figure‑8, s=stop
The Three Solvers At A Glance
- CCD: rotate each joint (from tip to base) to reduce the angle between the joint‑to‑effector and joint‑to‑target vectors. Repeat until close enough.
- FABRIK: move joints along the line segments in two passes (end→base, then base→end) while keeping segment lengths fixed.
- Jacobian‑Transpose: compute
J^T (target − effector)
to nudge angles in the direction that reduces error; a scalar step γ controls stability.
These are great building blocks. Real rigs add joint limits, damping, orientation goals, and regularization; but the core intuition transfers.
What You Can Do
- Drag the orange crosshair to set a new target; the arm follows.
- Hold Shift while dragging to reposition the green base and change reach.
- Toggle Reach Circle to see the maximum reachable radius
≈ sum(link lengths)
. - Enable Trace to visualize the end‑effector path while the solver converges.
- Experiment with links, length, and iterations to stress each algorithm.
- Switch algorithms mid‑motion to compare convergence style and stability.
New tricks:
- Turn on Joint Limits, adjust ±deg, and optionally show limit arcs at each joint.
- Add Rest Pose Bias and set/reset the current configuration as the preferred pose.
- Drive the target along a Circle or Figure‑8 and tune the speed.
- Show Metrics to plot the error over time in the top‑right.
Try These Presets
- Many short links: set
Links=10
,Link Length=40–60
,Iterations=16+
; compare CCD vs. FABRIK convergence speed and smoothness. - Unreachable target: drag outside the reach circle; observe boundary behavior across solvers.
- Tracking a path: enable Figure‑8 at moderate speed; compare lag/overshoot for JT vs. DLS while tuning
γ
andλ
. - Joint limits: enable limits at ±60–90° and toggle “Show Limit Arcs”; note how each solver adapts.
Share a Setup
The demo reads settings from the URL, so you can share a preset. Example:
?algo=dls&n=6&L=80&it=16&la=3&d=0.7&rg=1&tr=1&mv=eight&sp=1.2
Parameters: algo (ccd | fabrik | jt | dls), n (links), L (link length), it (iterations/frame), g (JT γ), la (DLS λ), d (damping), px (pause 0/1), rg (reach circle 0/1), tr (trace 0/1), lm (limits 0/1), ld (limit degrees), sl (show limit arcs 0/1), rb (rest bias), mv (none | circle | eight), sp (target speed), mx,my (base), tx,ty (target). |
What To Look For
- CCD progresses joint‑by‑joint from the end: you’ll see a “snake‑like” motion.
- FABRIK tends to straighten lines and converge quickly in a few passes.
- Jacobian‑Transpose makes smooth, simultaneous angle updates; with a too‑large step it can overshoot or oscillate—reduce γ or increase damping.
- When the target is outside the reach circle, the end‑effector settles on the boundary in the closest direction.
Problem Setup (2D Planar Chain)
- Goal: find angles
θ = [θ1..θn]
so the end‑effector positionp(θ)
matches a targett
. - Links are length
L
with a fixed base, so forward kinematics sums rotations and offsets. - We minimize position error
e = t − p(θ)
; different methods updateθ
differently.
CCD (Cyclic Coordinate Descent)
- Idea: for joint
i
(from end to base), rotate to reduce the angle between vectors(joint_i → effector)
and(joint_i → target)
. - Pros: dead simple, robust, no matrices; handles unreachable cases gracefully.
- Cons: can be slow for long chains; path can look “wiggly”.
Pseudo‑steps per sweep:
for i = n-1 down to 0:
a1 = angle(j_i → end_effector)
a2 = angle(j_i → target)
θ_i += wrap_to_pi(a2 - a1) * damping
forward_kinematics()
FABRIK (Forward And Backward Reaching IK)
- Idea: operate in position space, preserving segment lengths with two passes.
- Backward: place the end at the target and pull joints back along lines to keep lengths.
- Forward: pin the base, then push joints forward to keep lengths.
- Pros: fast convergence, numerically stable, no Jacobians.
- Cons: handling joint limits and constraints needs extra steps.
Pseudo‑steps per iteration:
// If unreachable: point segments toward target and stop.
end = target
for i = n-1..0: j_i = j_{i+1} + L * normalize(j_i - j_{i+1})
base stays fixed
for i = 0..n-1: j_{i+1} = j_i + L * normalize(j_{i+1} - j_i)
Jacobian Transpose (JT)
- Idea: small changes in angles
Δθ
change the end positionΔp ≈ J Δθ
, whereJ
is the 2×n Jacobian. Use the gradient directionΔθ = α J^T (t − p)
. - In this demo we use an adaptive step
α = (r·(J J^T r)) / (||J J^T r||² + ε)
and clamp it toγ
for stability. - Pros: smooth simultaneous joint updates; extensible to orientation, weights, damping.
- Cons: can oscillate near singularities without step control; needs tuning.
Update rule used here:
u = J^T r // per-joint update direction
v = J u // predicted end-effector motion
α = clamp( (r·v) / (v·v + ε), 0, γ )
θ ← θ + α u * damping
Jacobian for a Planar Chain (2D)
- For joint i at position
p_i = (x_i, y_i)
and the end‑effector ate = (x_e, y_e)
, the Jacobian column with respect toθ_i
is[−(y_e − y_i), (x_e − x_i)]
. - This geometric form (a perpendicular to the joint→end vector) is what the demo uses for both JT and DLS updates.
Damped Least Squares (DLS)
- Idea: take a regularized least‑squares step
Δθ = J^T (J J^T + λ^2 I)^{-1} r
to temper ill‑conditioned directions near singularities. - Pros: very robust near straight chains and during fast motions; reduces oscillations.
- Cons: requires tuning
λ
(too large = sluggish, too small = oscillation like plain LS).
Pseudo‑step (2D task):
A = J J^T + λ^2 I // 2×2 in this demo
y = A^{-1} r
Δθ = J^T y
θ ← θ + Δθ * damping
Tuning: raise λ
for stability (less aggressive updates), lower it for responsiveness. Combine with global Damping
for smooth paths.
Reachability and Behavior at the Limits
- If the target is outside the reach circle, all methods align the chain toward the target and settle on the boundary.
- With very short link lengths and many segments, JT can take smaller steps—raise
iterations
or lowerγ
to avoid oscillations. - FABRIK quickly finds boundary solutions; CCD will crawl along the boundary as joints adjust.
Singularities & Stability
- Near singular configurations (e.g., a straight chain), the Jacobian is ill‑conditioned and naive gradient steps can oscillate.
- Jacobian‑Transpose here uses an adaptive step
α
clamped byγ
(JT Step) to curb overshoot; lowerγ
or raiseDamping
if you see ringing. - DLS regularizes with
λ
inside(J J^T + λ^2 I)^{-1}
; increaseλ
near singularities for stable tracking. - With moving targets, compare lag vs. robustness: JT with tuned
γ
reacts quickly; DLS trades a bit of lag for smoother motion.
Practical Tips
- Increase
Iterations/Frame
to accelerate convergence at the cost of CPU. - Lower
γ
and/or increaseDamping
if JT jitters; raiseγ
if progress is too slow. - More links can make CCD slower; FABRIK scales well; JT prefers well‑scaled lengths.
- For smooth paths, enable Trace and compare the motion across solvers.
Extensions You Might Add
- Joint limits: clamp per‑joint
θ_i
after each update. - Regularization: add damping in JT/DLS to handle singularities better.
- Orientation goals: extend to 3D and include end‑effector orientation constraints.
- Obstacles: project joints away from obstacles between passes.
- Targets over time: follow a moving target and compare lag/overshoot.
When to Use Which
- Use CCD for small rigs, quick prototypes, or when simplicity wins.
- Use FABRIK for character rigs and many‑link chains where fast, stable convergence is desired.
- Use Jacobian methods for combining multiple objectives (position + orientation + soft constraints) and when you’ll need weights or task‑space control.
References and Further Reading
- Aristidou & Lasenby, “FABRIK: A fast, iterative solver for the Inverse Kinematics problem” (2011)
- Buss, “Introduction to Inverse Kinematics with Jacobian Methods” (2004)
- Tolani, Goswami, & Badler, “Real-Time Inverse Kinematics Techniques for Anthropomorphic Limbs” (2000)
- Wampler, “Manipulator Inverse Kinematic Solutions Based on Vector Formulations and Damped Least‑Squares Methods” (1986)
- Nakamura & Hanafusa, “Inverse kinematics solutions with singularity avoidance for robot manipulator control” (1986)
- Maciejewski & Klein, “Obstacle avoidance for kinematically redundant manipulators in dynamically varying environments” (1985)