5. Differential Kinematics and Statics

Whereas direct kinematics is a static map (joints → pose), differential kinematics is its instantaneous derivative: how do joint rates map to end-effector velocities? The central tool is the Jacobian matrix. The same Jacobian, transposed, maps end-effector forces and moments back to joint torques — a duality that connects velocity control to force control and underpins much of robot statics.

Note

Two different Jacobians appear in the literature. The analytical Jacobian \(\mathbf{J}_A = \partial h / \partial \boldsymbol q\) arises from differentiating the pose map directly. The geometric Jacobian \(\mathbf{J}\) maps joint rates to the physical twist (linear velocity + angular velocity). In general \(\mathbf{J}\neq \mathbf{J}_A\); they agree only when the chosen orientation parameterisation has the property \(\dot{\boldsymbol\phi} = \boldsymbol\omega_e\), which is not the case for Euler angles. The distinction matters: using \(\mathbf{J}_A\) where \(\mathbf{J}\) is required leads to errors in velocity and force calculations.

1 From pose to velocity

Differentiating the direct kinematics map \(\boldsymbol x = h(\boldsymbol q)\) gives

\[ \dot{\boldsymbol x} = \frac{\partial h}{\partial \boldsymbol q}\,\dot{\boldsymbol q} = \underbrace{\mathbf{J}_A(\boldsymbol q)}_{\text{analytical Jacobian}}\dot{\boldsymbol q}. \]

However, \(\dot{\boldsymbol\phi}\) (the time derivative of an orientation parameterisation) is generally not the angular velocity vector \(\boldsymbol\omega\). It is therefore more natural to work with the geometric Jacobian that maps joint rates directly to the end-effector twist.

2 Derivative of a rotation matrix

Differentiating the orthogonality identity \(\mathbf{R}(t)\mathbf{R}(t)^{\mathsf{T}}= \mathbf I\) gives

\[ \dot{\mathbf{R}}(t)\mathbf{R}(t)^{\mathsf{T}}+ \mathbf{R}(t)\dot{\mathbf{R}}(t)^{\mathsf{T}}= \mathbf 0 . \]

Define \(\mathbf S(t) = \dot{\mathbf{R}}(t)\mathbf{R}(t)^{\mathsf{T}}\). Since \(\mathbf S + \mathbf S^{\mathsf{T}}= \mathbf 0\), \(\mathbf S\) is skew-symmetric and corresponds to a cross product:

\[ \mathbf S(\boldsymbol\omega) = \begin{bmatrix} 0 & -\omega_z & \omega_y\\ \omega_z & 0 & -\omega_x\\ -\omega_y & \omega_x & 0 \end{bmatrix}, \qquad \boldsymbol\omega \times \boldsymbol b = \mathbf S(\boldsymbol\omega)\,\boldsymbol b. \]

Rearranging gives the matrix differential equation for a rotating body:

\[ \boxed{\;\dot{\mathbf{R}}(t) = \mathbf S(\boldsymbol\omega)\,\mathbf{R}(t)\;} \]

For a point fixed in the body, \(\boldsymbol{p}= \mathbf{R}(t)\boldsymbol{p}'\), so

\[ \dot{\boldsymbol{p}} = \dot{\mathbf{R}}\boldsymbol{p}' = \mathbf S(\boldsymbol\omega)\mathbf{R}\boldsymbol{p}' = \boldsymbol\omega \times \mathbf{R}\boldsymbol{p}' = \boldsymbol\omega \times \boldsymbol{p}, \]

recovering the familiar formula \(\boldsymbol v = \boldsymbol\omega\times\boldsymbol r\). A useful conjugation identity is \(\mathbf{R}\,\mathbf S(\boldsymbol\omega)\,\mathbf{R}^{\mathsf{T}}= \mathbf S(\mathbf{R}\boldsymbol\omega)\).

3 Link velocity propagation

The angular and linear velocities propagate outward from the base along the chain, one joint at a time. The derivation uses a single rule from rigid-body mechanics: the velocity of any point on a rigid body equals the velocity of a reference point on that body plus the cross product of the angular velocity with the relative position vector.

For joint \(i\):

Revolute joint: adds a rotation about \(\hat z_{i-1}\) at rate \(\dot\theta_i\):

\[ \boldsymbol\omega_i = \boldsymbol\omega_{i-1} + \dot\theta_i\,\hat z_{i-1}. \]

The linear velocity of the next frame origin gains a cross-product term: \(\dot{\boldsymbol{p}}_i = \dot{\boldsymbol{p}}_{i-1} + \boldsymbol\omega_i \times (\boldsymbol{p}_i - \boldsymbol{p}_{i-1})\).

Prismatic joint: translates along \(\hat z_{i-1}\) at rate \(\dot d_i\) but adds no rotation:

\[ \boldsymbol\omega_i = \boldsymbol\omega_{i-1}, \qquad \dot{\boldsymbol{p}}_{i} = \dot{\boldsymbol{p}}_{i-1} + \dot d_i\,\hat z_{i-1}. \]

Applying the rigid-body rule recursively from the fixed base (\(\boldsymbol\omega_0=0\), \(\dot{\boldsymbol{p}}_0=0\)) accumulates contributions from every joint in the chain up to the end-effector.

4 The geometric Jacobian

Collecting the velocity contributions, the end-effector twist is

\[ \boldsymbol v_e = \begin{bmatrix}\dot{\boldsymbol{p}}_e\\ \boldsymbol\omega_e\end{bmatrix} = \begin{bmatrix}\mathbf{J}_P\\ \mathbf{J}_O\end{bmatrix}\dot{\boldsymbol q} = \mathbf{J}(\boldsymbol q)\,\dot{\boldsymbol q}. \]

Each column of \(\mathbf{J}\) is the velocity contribution of one joint:

\[ \begin{bmatrix}\mathbf{J}_{P_i}\\ \mathbf{J}_{O_i}\end{bmatrix} = \underbrace{\begin{bmatrix}\hat z_{i-1}\\ \mathbf 0\end{bmatrix}}_{\text{prismatic}} \qquad\text{or}\qquad \underbrace{\begin{bmatrix}\hat z_{i-1}\times(\boldsymbol{p}_e - \boldsymbol{p}_{i-1})\\ \hat z_{i-1}\end{bmatrix}}_{\text{revolute}} . \]

The geometric quantities \(\hat z_{i-1}\), \(\boldsymbol{p}_e\), \(\boldsymbol{p}_{i-1}\) are read from the direct-kinematics transforms \(\mathbf{A}^0_1\cdots\mathbf{A}^{*}_{*}\):

\[ \hat z_{i-1} = \mathbf{R}^0_1(q_1)\cdots\mathbf{R}^{i-2}_{i-1}(q_{i-1})\,\hat z_0, \qquad \hat z_0 = [0,0,1]^{\mathsf{T}}. \]

4.2 Example: anthropomorphic arm

With DH parameters as in ?@tbl-anthro, the relevant axes are \(\hat z_0=[0,0,1]^{\mathsf{T}}\), \(\hat z_1=\hat z_2=[s_1,-c_1,0]^{\mathsf{T}}\), \(\boldsymbol{p}_0=\boldsymbol{p}_1=[0,0,0]^{\mathsf{T}}\), and

\[ \boldsymbol{p}_2 = \begin{bmatrix}a_2 c_1 c_2\\ a_2 s_1 c_2\\ a_2 s_2\end{bmatrix}, \qquad \boldsymbol{p}_3 = \begin{bmatrix}c_1(a_2 c_2 + a_3 c_{23})\\ s_1(a_2 c_2 + a_3 c_{23})\\ a_2 s_2 + a_3 s_{23}\end{bmatrix}. \]

Carrying out the cross products yields

\[ \mathbf{J}= \begin{bmatrix} -s_1(a_2 c_2 + a_3 c_{23}) & -c_1(a_2 s_2 + a_3 s_{23}) & -c_1 a_3 s_{23}\\ \;\;c_1(a_2 c_2 + a_3 c_{23}) & -s_1(a_2 s_2 + a_3 s_{23}) & -s_1 a_3 s_{23}\\ 0 & a_2 c_2 + a_3 c_{23} & a_3 c_{23}\\ 0 & s_1 & s_1\\ 0 & -c_1 & -c_1\\ 1 & 0 & 0 \end{bmatrix}. \]

5 Singularities

A kinematic singularity occurs where \(\mathbf{J}\) loses rank — one or more directions of end-effector motion become unattainable regardless of the joint rates. For the planar 2R arm,

\[ \mathbf{J}= \begin{bmatrix} -a_1 s_1 - a_2 s_{12} & -a_2 s_{12}\\ \;\;a_1 c_1 + a_2 c_{12} & \;\;a_2 c_{12} \end{bmatrix}, \qquad \det \mathbf{J}= a_1 a_2 s_2 . \]

Hence \(\det\mathbf{J}= 0\) exactly when \(\theta_2 = 0\) or \(\theta_2 = \pi\), corresponding to the arm fully stretched (boundary singularity) or fully folded (internal singularity). Near singularities small end-effector velocities require very large joint rates, and inverse kinematics solutions become numerically ill-conditioned.

6 Analytical Jacobian and representation singularities

Important

\(\mathbf{J}\neq \mathbf{J}_A\) in general. The analytical Jacobian \(\mathbf{J}_A = \partial h/\partial\boldsymbol q\) is the partial derivative of the pose map, while the geometric Jacobian \(\mathbf{J}\) maps joint rates to the physical twist. They differ because \(\dot{\boldsymbol\phi} \neq \boldsymbol\omega_e\) in general — the time derivative of an orientation parameterisation is not the same as the angular velocity vector.

For a ZYZ parameterisation \(\boldsymbol\phi=[\varphi,\vartheta,\psi]^{\mathsf{T}}\), the angular velocity is

\[ \boldsymbol\omega_e = \underbrace{\begin{bmatrix} 0 & -s_\varphi & c_\varphi s_\vartheta\\ 0 & c_\varphi & s_\varphi s_\vartheta\\ 1 & 0 & c_\vartheta \end{bmatrix}}_{\mathbf T(\boldsymbol\phi_e)} \dot{\boldsymbol\phi}, \]

so the full velocity transform is

\[ \boldsymbol v_e = \begin{bmatrix}\mathbf I & \mathbf 0\\ \mathbf 0 & \mathbf T(\boldsymbol\phi_e)\end{bmatrix} \dot{\boldsymbol x}_e = \mathbf T_A\,\dot{\boldsymbol x}_e, \qquad \mathbf{J}= \mathbf T_A\,\mathbf{J}_A . \]

When \(\mathbf T(\boldsymbol\phi_e)\) is singular (at \(s_\vartheta = 0\)), the orientation parameterisation hits a representation singularity (also called gimbal lock). This is distinct from a kinematic singularity of the arm itself and can be avoided by switching orientation representation mid-trajectory.

7 Statics

7.1 Wrench and joint torques

At static equilibrium the end-effector exerts a wrench

\[ \boldsymbol\gamma_e = \begin{bmatrix}\boldsymbol F_e\\ \boldsymbol\mu_e\end{bmatrix} \]

(force \(\boldsymbol F_e\) and moment \(\boldsymbol\mu_e\)), and the joints carry generalised torques \(\boldsymbol\tau = [\tau_1,\dots,\tau_n]^{\mathsf{T}}\).

7.2 Virtual work duality

Apply virtual joint displacements \(\delta\boldsymbol q\). The virtual work of the joint torques is \(\boldsymbol\tau^{\mathsf{T}}\delta\boldsymbol q\). The virtual work of the wrench is

\[ \boldsymbol F_e^{\mathsf{T}}\,\delta\boldsymbol{p}_e + \boldsymbol\mu_e^{\mathsf{T}}\,\boldsymbol\omega_e\,\delta t = \boldsymbol\gamma_e^{\mathsf{T}}\,\mathbf{J}\,\delta\boldsymbol q. \]

Setting internal and external virtual work equal for arbitrary \(\delta\boldsymbol q\):

\[ \boxed{\;\boldsymbol\tau = \mathbf{J}^{\mathsf{T}}(\boldsymbol q)\,\boldsymbol\gamma_e\;} \]

The transpose of the same Jacobian that maps joint rates to end-effector velocity maps end-effector wrenches to joint torques. This kinematic–static duality is a fundamental result: it means that a manipulator’s force capability in task space is directly determined by its velocity mapping in joint space.

In particular, near a singularity the Jacobian loses rank, so the manipulator can exert large forces in certain directions while losing the ability to generate forces in others.