Theoretical Background: Velocity Kinematics
Module 3 Theory: The Jacobian for 2-DOF Systems
3.1.1 What is the Jacobian?
Forward kinematics maps joint positions to end-effector position: . In robotics, we frequently need the velocity-level relationship: given how fast each joint is moving, how fast is the end-effector moving? The Jacobian matrix provides this mapping.
Definition: The Jacobian is the matrix of first-order partial derivatives of the forward kinematics mapping, relating joint velocities to end-effector velocities:
where is the end-effector velocity vector, is the joint velocity vector, and is configuration-dependent — its entries change as the robot moves.
Key Concept: The Jacobian is not a single fixed matrix. It must be recomputed at every configuration because the relationship between joint motion and end-effector motion depends on the robot’s current pose.
Small Displacement Approximation: For small changes in joint angles, the Jacobian provides a linear approximation of the resulting end-effector displacement:
This approximation becomes exact in the limit as . It is the foundation for iterative inverse kinematics algorithms, where small corrections in joint space produce small corrections in task space.
Dimensions: For a robot with joints performing a task described in dimensions, the Jacobian is an matrix. For a 2-DOF planar robot moving in a 2D plane, is a square matrix — a particularly convenient case because a square Jacobian can be directly inverted when it is nonsingular.
3.1.2 Constructing the 2-DOF Planar Jacobian
Consider a planar robot with two revolute joints, link lengths and , and joint angles and . The forward kinematics gives the end-effector position as:
To construct the Jacobian, we differentiate each component of the end-effector position with respect to each joint variable. The partial derivatives are:
Assembling these into matrix form:
Physical Meaning of Each Column:
- Column 1 of represents the end-effector velocity that results from rotating only joint 1 at unit speed (, ). This is a velocity vector tangent to a circle centred at joint 1.
- Column 2 of represents the end-effector velocity that results from rotating only joint 2 at unit speed (, ). This is a velocity vector tangent to a circle centred at joint 2.
The total end-effector velocity is the weighted sum of these columns, with the weights being the respective joint velocities. This column-wise interpretation is crucial for building geometric intuition about how each joint contributes to end-effector motion.
3.1.3 Singularity Analysis
The determinant of the Jacobian is:
Singularity Condition: The Jacobian becomes singular () when , which occurs at:
- (extended configuration): Both links are fully stretched out in a line. The end-effector cannot move radially inward or outward — it can only move perpendicular to the arm.
- (folded configuration): Both links are folded back on each other. The end-effector again loses one direction of mobility.
Physical Consequences of Singularity:
- Loss of degrees of freedom: At a singularity, the end-effector cannot generate velocity in at least one task-space direction, regardless of how fast the joints move. The two column vectors of become parallel, spanning only a one-dimensional subspace.
- Infinite joint velocities: If the desired end-effector velocity has any component in the singular direction, the required joint velocities become unbounded as the configuration approaches singularity. This is because contains , which diverges as .
- Force amplification near singularities: By the velocity-force duality (Section 3.1.5), the directions in which the robot loses velocity capability are precisely the directions in which it gains force capability. Near a fully extended configuration, the robot can exert large forces along the arm direction but cannot move in that direction.
Practical Implication: Robot controllers must detect proximity to singularities and either avoid them through trajectory planning, or use damped inverse methods to prevent joint velocity saturation.
3.1.4 Manipulability
Yoshikawa’s Manipulability Index: A scalar measure of how well the robot can generate end-effector velocities at a given configuration:
- at a singularity (no ability to move in all directions)
- Larger indicates better ability to generate velocities in all task-space directions
- For the 2-DOF planar robot: , which is maximised when or (elbow bent at 90 degrees)
Manipulability Ellipsoid: The set of all end-effector velocities achievable by unit-norm joint velocities () forms an ellipsoid in task space. The principal axes of this ellipsoid indicate the directions along which the robot can move most and least easily, and their lengths indicate the corresponding velocity magnitudes.
Singular Value Decomposition (SVD): The shape of the manipulability ellipsoid is revealed by the SVD of the Jacobian:
where is a orthogonal matrix whose columns are the principal directions in task space, contains the singular values (semi-axis lengths of the ellipsoid), and is a orthogonal matrix whose columns are the corresponding directions in joint space.
Condition Number: The ratio measures the eccentricity of the manipulability ellipsoid. A condition number of 1 () means the ellipsoid is a circle, indicating isotropic manipulation capability. A large condition number means the robot can move much more easily in some directions than others, and the robot is close to a singularity when the condition number approaches infinity.
3.1.5 Velocity-Force Duality
The Jacobian also governs the relationship between end-effector forces and joint torques. If the end-effector exerts a force on the environment, the equivalent joint torques are:
This is derived from the principle of virtual work: the power at the joints must equal the power at the end-effector, so , which must hold for all , giving .
Key Insight – Velocity-Force Trade-Off:
- Near singularity: The robot has large force capability in the singular direction but cannot generate velocity in that direction. Think of pushing along the axis of a fully extended arm — enormous force, no movement.
- Away from singularity: The robot has balanced velocity and force capabilities in all directions.
- The velocity advantage in any direction is the reciprocal of the force advantage: if the robot can generate the velocity in one direction versus another, it can only generate the force in that direction.
This is the robotic equivalent of a mechanical lever: you trade speed for force or vice versa, depending on the configuration.
3.1.6 Numerical Example
Given: A 2-DOF planar robot with , , at configuration , . Joint velocities are , .
Step 1 – Compute trigonometric values:
Step 2 – Compute Jacobian entries:
Step 3 – Compute determinant and manipulability:
Using Equation (6) as a check: . Confirmed.
Step 4 – Compute end-effector velocity:
The end-effector moves at approximately in the direction , which is primarily leftward and slightly upward.
Step 5 – Interpret manipulability:
The manipulability is less than the maximum possible value of , indicating the robot is not at its most dexterous configuration. The maximum manipulability occurs at , where .
Script Implementation
# Python: compute Jacobian for 2-DOF planar robot
# Shows numerical evaluation at a specific configuration
import numpy as np
def jacobian_2dof(q, l1, l2):
# Extract joint angles
theta1, theta2 = q
# Precompute trigonometric terms
s1 = np.sin(theta1); c1 = np.cos(theta1)
s12 = np.sin(theta1 + theta2); c12 = np.cos(theta1 + theta2)
# Assemble 2x2 Jacobian -- Eq. (5)
J = np.array([[-l1*s1 - l2*s12, -l2*s12],
[ l1*c1 + l2*c12, l2*c12]])
return J
def manipulability(J):
# Yoshikawa's index -- Eq. (7)
return abs(np.linalg.det(J))
def force_mapping(J, F):
# Joint torques from end-effector force -- Eq. (9)
return J.T @ F
# Define robot parameters
l1 = 0.5; l2 = 0.4
q = np.array([np.pi/4, np.pi/3])
q_dot = np.array([1.0, -0.5])
# Compute Jacobian
J = jacobian_2dof(q, l1, l2)
print("Jacobian:\n", J)
# Compute end-effector velocity -- Eq. (1)
x_dot = J @ q_dot
print("End-effector velocity:", x_dot)
# Compute manipulability
w = manipulability(J)
print("Manipulability:", w)
# Compute condition number via SVD -- Eq. (8)
U, sigma, Vt = np.linalg.svd(J)
print("Singular values:", sigma)
print("Condition number:", sigma[0] / sigma[1])
# Compute joint torques for a unit force in x-direction -- Eq. (9)
F = np.array([1.0, 0.0])
tau = force_mapping(J, F)
print("Joint torques for F=[1,0]:", tau)
Bridge to the Course 3-DOF Platform
The 2-DOF planar derivation above extends directly to the 3-DOF anthropomorphic arm on
the course platform at /robot-arm. The pure-math library
frontend/lib/Robot/arm3dof.ts implements a 3R configuration — a base revolute
about the world -axis, a shoulder, and an elbow — with default link lengths
m (base column), m, and m. The exported
jacobianAnalytical(q, p) function returns a position Jacobian; the
companion analyseJacobian(q, p) returns the packed result
— the Yoshikawa manipulability (Equation (7)
generalised to square ) and the condition number you studied above.
Two specialisations recover the 2-DOF case exactly. Fixing collapses the base rotation, leaving the shoulder–elbow plane; the resulting sub-block of the Jacobian is structurally identical to Equation (5) under the substitutions , and an offset along by . This is exactly the identity students verify in Lab 2 Task 6.
The platform ships a damped-least-squares regulariser with default
, (exported as DEFAULT_DLS),
activated whenever the live manipulability drops below . Driving the arm to
on /robot-arm lets you watch DLS kick in — the control law smoothly
interpolates between and a damped inverse as the singularity is approached,
which is the practical resolution of the “” blow-up discussed above.
Integration: Theory to Practice
The Jacobian is computed at every control cycle from encoder readings of and . In resolved-rate control, the desired end-effector velocity is specified by the task planner, and the controller inverts the Jacobian to determine the required joint velocities at each timestep. The manipulability index is monitored online to detect proximity to singularities and trigger avoidance behaviours. In force control applications, the transpose Jacobian maps measured end-effector forces to equivalent joint torques, enabling compliant interaction with the environment. For the 2-DOF case, the Jacobian is a matrix and its inverse is computed analytically using the classical adjugate formula, avoiding the computational cost of numerical inversion. This direct inverse is one of the key advantages of studying the square Jacobian case before moving to redundant or under-actuated systems.
Theoretical Design Choices
The 2-DOF planar robot is chosen as the canonical system for introducing the Jacobian because it captures all essential phenomena — configuration dependence, singularities, manipulability, and velocity-force duality — while remaining analytically tractable. The Jacobian permits a closed-form determinant (), making singularity analysis transparent: singularities occur exactly when the elbow is fully extended or fully folded. The square structure of the Jacobian means that a direct inverse exists for non-singular configurations, avoiding the need for pseudo-inverse or optimization-based methods that are required for redundant systems. This allows students to build physical intuition about the velocity-force trade-off before encountering the additional mathematical machinery needed for general -DOF manipulators. The choice of analytical differentiation (rather than geometric construction) to derive the Jacobian reinforces the connection between forward kinematics and velocity kinematics, and generalises naturally to more complex kinematic structures.