RobotForge
Published·~14 min

Inverse kinematics: analytical solutions

Given a target (x, y), find the joint angles. Closed-form IK for a 2-DOF planar arm, the two-solution trap (elbow up vs elbow down), and when closed-form falls apart.

by RobotForge
#kinematics#inverse-kinematics#arm

Forward kinematics answers "where is the hand?" given joint angles. Inverse kinematics answers the harder, more useful question: "what joint angles get the hand to that point?" Useful in every pick-and-place, every drawing robot, every arm you'll ever build. Let's derive the closed-form answer for a 2-DOF planar arm.

The setup

Same arm as the forward-kinematics lesson. Shoulder at origin, link lengths L1 and L2, joint angles θ1 and θ2. We were given:

x = L1 cos(θ1) + L2 cos(θ1 + θ2)
y = L1 sin(θ1) + L2 sin(θ1 + θ2)

Now we want to solve for θ1, θ2 given a target (x, y). Two equations, two unknowns. Doable.

The derivation

Square and add both equations:

x² + y² = L1² + L2² + 2·L1·L2·cos(θ2)

cos(θ2) = (x² + y² − L1² − L2²) / (2·L1·L2)

That gives us θ2 directly (well, two values: ±acos(...)).

Now we need θ1. A clean way: decompose into two angles.

α = atan2(y, x)                                    # angle of target from origin
β = atan2(L2·sin(θ2), L1 + L2·cos(θ2))             # angle of link2 relative to link1 vector

θ1 = α − β

Five lines of trig. Two unknowns solved.

The two-solution trap

The cos(θ2) equation has two solutions: θ2 = +acos(...) (elbow down) and θ2 = −acos(...) (elbow up). Both are valid arm configurations that reach the target. Which to pick?

shoulder elbow ↑ elbow up shoulder elbow ↓ elbow down same (x, y) same (x, y)
Both configurations reach the same end-effector (x, y). Pick one based on joint limits or proximity to the current pose.

For a real arm:

  • Pick the configuration with lower joint velocities to get there from the current pose.
  • Or pick the one that's farther from joint limits.
  • Or just always pick "elbow up" if your arm has a preferred working configuration.

If you forget this and always take +acos, your arm will sometimes do surprising flips when crossing certain target points. That's the elbow singularity, one of the most common IK bugs.

Python implementation

import math

def inverse_kinematics_2dof(x, y, L1, L2, elbow_up=True):
    """Return (theta1, theta2) that place the end-effector at (x, y).

    Raises ValueError if the target is unreachable.
    """
    r2 = x**2 + y**2
    r = math.sqrt(r2)

    if r > L1 + L2:
        raise ValueError(f'Target too far: {r:.3f} > {L1+L2}')
    if r < abs(L1 - L2):
        raise ValueError(f'Target too close: {r:.3f} < {abs(L1-L2)}')

    cos_t2 = (r2 - L1**2 - L2**2) / (2 * L1 * L2)
    cos_t2 = max(-1.0, min(1.0, cos_t2))   # numerical safety
    t2 = math.acos(cos_t2)
    if not elbow_up:
        t2 = -t2

    alpha = math.atan2(y, x)
    beta = math.atan2(L2 * math.sin(t2), L1 + L2 * math.cos(t2))
    t1 = alpha - beta

    return t1, t2

Verify with forward kinematics

Always verify your IK by round-tripping through FK:

target = (1.2, 0.8)
t1, t2 = inverse_kinematics_2dof(*target, L1=1.0, L2=1.0)
x, y = forward_kinematics(t1, t2)
print(f'Target {target} → IK ({t1:.3f}, {t2:.3f}) → FK ({x:.3f}, {y:.3f})')

If FK(IK(target)) ≠ target (within numerical tolerance), your IK is wrong. This is the first test every IK implementation should pass.

What a reachability check does

The workspace is an annulus:

  • Outer radius: L1 + L2 (arm fully extended)
  • Inner radius: |L1 − L2| (arm folded back on itself)

Targets outside the outer radius are unreachable — no joint angles get the hand there. Targets inside the inner radius are also unreachable (the arm "can't reach in" past the folded configuration). The IK function raises in both cases.

On the boundary is the workspace singularity: θ2 = 0 or θ2 = π. The arm is fully extended or fully folded. Infinitesimally nearby targets require large joint velocities — the Jacobian loses rank. Real arms avoid this region because motions near it are violent.

When closed-form IK breaks down

For a 2-DOF planar arm, IK is closed-form, fast, and exact. For a 3-DOF planar arm with the hand also at a specific orientation, still closed-form. For a 6-DOF spherical-wrist arm (common industrial design), still closed-form — the problem decouples into position (first 3 joints) + orientation (last 3 joints).

For generic 7-DOF arms (Franka, Kinova), closed-form IK doesn't exist in the general case. There are infinite valid solutions (the extra DOF gives a "self-motion manifold"), and you need iterative (Jacobian-based) IK. That's the next lesson.

When to use analytical IK

  • Well-known arm geometries (2-DOF planar, 6-DOF spherical-wrist, SCARA).
  • Tight real-time loops where iterative solvers are too slow.
  • When you need predictable solutions (the analytical form is reproducible; iterative solvers depend on initial guesses).

When to switch to iterative

  • Redundant arms (7+ DOF).
  • Constraints beyond "reach this pose" — joint limits, obstacle avoidance, end-effector orientation preferences.
  • Non-standard mechanisms where the closed-form derivation is a nightmare.

Exercise

Implement IK for your 2-DOF arm. Pick 20 target points on a grid inside the reachable workspace. For each, compute both elbow-up and elbow-down solutions. Plot both arm configurations on the same figure. Watch yourself develop intuition for what "the elbow flips" looks like geometrically — you'll recognize it in every IK bug you ever debug.

Try it: drag the target

shoulderelbowtarget
x = 0.90y = 0.60θ₁ = -5.4°θ₂ = 103.2°
Click or drag inside the SVG to move the target. Watch the arm solve in real time. Toggle the elbow configuration to see the second IK solution at the same target.

Comments

    Sign in to post a comment.