Velocity Kinematics#
Notation convention warning of this lecture: if a vector has no superscript, it means this vector is expressed in the world frame by default; otherwise, the frame the coordinates of this vector is with respect to will be specified on its superscript.
Derivative of Rotation Matrix#
Consider a time-varying rotation matrix \(\boldsymbol{R}=\boldsymbol{R}(t)\). Based on the property of rotation matrix, we always have
Differentiating the above equation with respect to time gives
Let’s define a new matrix
Then,
Any matrix that satisfies the above equation is called skew-symmetric matrix (a square matrix whose transpose equals its negative).
From (4), we have
Now, let’s find out what is \(\boldsymbol{S}\) and its physics interpretation.
Suppose \({\boldsymbol{R}}\) represents a rotation of a moving body frame \(O'-x'y'z'\) with respect to a fixed reference frame \(O-xyz\). Let’s consider a point \(P\), rigidly fixed to the body frame (thus moving as body is moving), with its body frame coordinate \(\boldsymbol{p}^{\prime}\). Then, its coordinate in the reference frame \(\boldsymbol{p}\) is
which is time varying.
Taking the derivative to both sides of (6) yields
where we have used (4).
Recall in your mechanics courses, given the angular velocity \(\boldsymbol{\omega}\) of a moving body with respect to a reference frame, any point \(P\) fixed on this body has a velocity in the reference frame as
where \(\boldsymbol{\omega}=\left[\begin{array}{lll}\omega_{x} & \omega_{y} & \omega_{z}\end{array}\right]^{T}\) is the angular velocity of the moving body, expressed in the reference frame.
If we compare (7) and (8), we can find
Thus, this skew-symmetric matrix \(\boldsymbol{S}\) can be obtained directly from the body’s angular velocity \(\boldsymbol{\omega}\). We typically write it as \(\boldsymbol{S}(\boldsymbol{\omega})\).
In sum, we can conclude the derivative of a rotation matrix is
Note that the above angular velocity \(\boldsymbol{\omega}\) is expressed in the reference frame!
One property of \(\boldsymbol{S}(\boldsymbol{\omega})\): For any rotation matrix \(\boldsymbol{R}\), one has
Derivative of Rotation + Translation#
Consider a transformation mapping the coordinate mapping of a point \(P\) (NOT necessarily fixed on a moving body) from the body frame \(O_1-x_1y_1z_1\) to reference frame \(O_0-x_0y_0z_0\)
Differentiating the above equation with respect to time yields
In (10), when \(P\) is moving on the body, it will have a local velocity \(\dot{{\boldsymbol{p}}}^{1}\) in the in the body frame. Note that the second line is derived due to \(\boldsymbol{R}_{1}^{0} \boldsymbol{p}^{1}=\boldsymbol{p}^{0}\) and \(\boldsymbol{S}\left(\boldsymbol{\omega}_{1}^{0}\right)=[\omega_{1}^{0} \times] \).
Notice that, if \(\boldsymbol{p}^{1}\) is fixed in the moving body frame , (10) becomes
Apply to links of a robot arm#
Consider the Link \(i\) of a robot arm in Fig. 53 (the frames follow the DH convention). Let \(\boldsymbol{r}_{i-1, i}^{i-1}\) denote the position of the origin of Frame \(i\) from the origin of Frame \(i-1\), expressed in Frame \(i-1\).
Before we proceed, a quick question: how to obtain \(\boldsymbol{p}_{i-1}\) and \(\boldsymbol{R}_{i-1}\)? and how to obtain \(\boldsymbol{r}_{i-1, i}^{i-1}\)?

Fig. 53 Link \(i\) of a robot arm#
Linear (Translational) Velocity#
The position of Frame \(i\) is
Similar to (10), taking the derivative of both sides in the above equation with respect to time \(t\), we have
Here, we define \(\boldsymbol{v}_{i-1, i}=\boldsymbol{R}_{i-1}\dot{\boldsymbol{r}}_{i-1, i}^{i-1}\), which is local translational velocity of Frame \(i\) in Frame \(i-1\), but expressed in the reference frame.
If joint \(i\) is revolute joint,
where \(\boldsymbol{\omega}_{i-1, i}\) is relative angular velocity of Frame \(i\) in Frame \(i-1\). More specifically,
What is \(\boldsymbol{z}_{i-1}\)? This is question for you!
Combine (12), (13) and (14), we have: If Joint \(i\) is revolute
If joint \(i\) is prismatic joint,
Combine (12), (13) and (15), we have: If Joint \(i\) is prismatic
Angular Velocity#
Next, let’s consider the rotation of Frame \(i\)
Its time derivative is
where \(\boldsymbol{\omega}_{i-1, i}^{i-1}\) denotes the angular velocity of Frame \(i\) with respect to Frame \(i-1\) expressed in Frame \(i-1\). The second term on the right-hand side of (16) can be rewritten as
by recalling the property of the skew-symmetric matrix in (9). Then,
If we cancel out all \( \boldsymbol{R}_{i}\) on both sides of (17), we can get
Thus, the angular velocity \(\boldsymbol{\omega}_{i}\) of Link \(i\) depends only on the angular velocity \(\boldsymbol{\omega}_{i-1}\) of Link \(i-1\) and their relative angular velocity \(\boldsymbol{\omega}_{i-1, i}\).
If joint \(i\) is revolute joint,
If joint \(i\) is prismatic.
Summary#
Considering different joint types for Joint \(i\) at a robot arm, according to (12) and (18), we can obtain
Important
If Joint \(i\) is prismatic
If Joint \(i\) is revolute