Velocity Kinematics#

Derivative of Rotation#

Consider a time-varying rotation matrix \(\boldsymbol{R}=\boldsymbol{R}(t)\). Based on the property of rotation matrix, we always have

\[\boldsymbol{R}(t) \boldsymbol{R}^{T}(t)=\boldsymbol{I}\]

Differentiating the above equation with respect to time gives

\[\dot{\boldsymbol{R}}(t) \boldsymbol{R}^{T}(t)+\boldsymbol{R}(t) \dot{\boldsymbol{R}}^{T}(t)=\boldsymbol{0}\]

Let’s define a new matrix

(4)#\[\boldsymbol{S}=\dot{\boldsymbol{R}} \boldsymbol{R}^{T}\]

Then, the above equation becomes

\[ \boldsymbol{S}+\boldsymbol{S}^{T}=\boldsymbol{0} \]

Any matrix that satisfies the above equation is called skew-symmetric matrix (a square matrix whose transpose equals its negative). From (4), we have

(5)#\[\dot{\boldsymbol{R}}=\boldsymbol{S} \boldsymbol{R}\]

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

(6)#\[\boldsymbol{p}(t)=\boldsymbol{R}(t) \boldsymbol{p}^{\prime}\]

which is time varying.

Taking the derivative to both sides of (6) yields

(7)#\[\dot{\boldsymbol{p}}=\dot{\boldsymbol{R}} \boldsymbol{p}^{\prime}=\boldsymbol{S} \boldsymbol{R} \boldsymbol{p}^{\prime}\]

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

(8)#\[ \dot{\boldsymbol{p}}=\boldsymbol{\omega} \times \boldsymbol{p}=\boldsymbol{\omega} \times \boldsymbol{R} \boldsymbol{p}^{\prime} \]

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 look at and compare (7) and (8), we can find

\[\begin{split}\boldsymbol{S}=[\boldsymbol{\omega} \times]=\boldsymbol{S}(\boldsymbol{\omega})=\left[\begin{array}{ccc} 0 & -\omega_{z} & \omega_{y} \\ \omega_{z} & 0 & -\omega_{x} \\ -\omega_{y} & \omega_{x} & 0 \end{array}\right]\end{split}\]

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

\[\dot{\boldsymbol{R}}=\boldsymbol{S}(\boldsymbol{\omega}) \boldsymbol{R}\]

Note that the above angular velocity \(\boldsymbol{\omega}\) is expressed in the reference frame! (not in the body frame)

One property of \(\boldsymbol{S}(\boldsymbol{\omega})\): For any rotation matrix \(\boldsymbol{R}\), one has

(9)#\[\boldsymbol{R} \boldsymbol{S}(\boldsymbol{\omega}) \boldsymbol{R}^{T}=\boldsymbol{S}(\boldsymbol{R} \boldsymbol{\omega})\]

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\)

\[\boldsymbol{p}^{0}=\boldsymbol{o}_{1}^{0}(t)+\boldsymbol{R}_{1}^{0}(t) \boldsymbol{p}^{1}\]

Differentiating the above equation with respect to time yields

(10)#\[\dot{\boldsymbol{p}}^{0}=\dot{\boldsymbol{o}}_{1}^{0}+\boldsymbol{R}_{1}^{0} \dot{\boldsymbol{p}}^{1}+\dot{\boldsymbol{R}}_{1}^{0} \boldsymbol{p}^{1}=\dot{\boldsymbol{o}}_{1}^{0}+\boldsymbol{R}_{1}^{0} \dot{{\boldsymbol{p}}}^{1}+\boldsymbol{S}\left(\boldsymbol{\omega}_{1}^{0}\right) \boldsymbol{R}_{1}^{0} \boldsymbol{p}^{1}\]

In the above (10), because point \(P\) is not necessarily fixed on the body, and it may have its local movement in the body frame with the local velocity \(\dot{{\boldsymbol{p}}}^{1}\). Special care should be paied to the notation of \(\dot{{\boldsymbol{p}}}^{1}\): \(\dot{{\boldsymbol{p}}}^{1}\) is purely taking the derivative to xyz body coordinate instead of body xyz axises.

Since \(\boldsymbol{R}_{1}^{0} \boldsymbol{p}^{1}=\boldsymbol{p}^{0}\) and \(\boldsymbol{S}\left(\boldsymbol{\omega}_{1}^{0}\right)=[\omega_{1}^{0} \times] \), the above equation (10) becomes

(11)#\[\dot{\boldsymbol{p}}^{0}=\dot{\boldsymbol{o}}_{1}^{0}+\boldsymbol{R}_{1}^{0} \dot{\boldsymbol{p}}^{1}+\omega_{1}^{0} \times \boldsymbol{p}^{0}\]

Here are some explaination of each term on the right side of (11):

  • \(\dot{\boldsymbol{o}}_{1}^{0}\) is the contribution to point \(P\)’s total velocity (in reference frame) by the translation of body frame.

  • \(\boldsymbol{R}_{1}^{0} \dot{\boldsymbol{p}}^{1}\) is the contribution to point \(P\)’s total velocity (in reference frame) by the local movement of \(P\) on the body frame. Here, \(\dot{\boldsymbol{p}}^{1}\) is the local velocity in the body frame, and \(\boldsymbol{R}_{1}^{0} \dot{\boldsymbol{p}}^{1}\) is the transformed local velocity to the reference frame.

  • \(\boldsymbol{S}\left(\boldsymbol{\omega}_{1}^{0}\right) \boldsymbol{R}_{1}^{0} \boldsymbol{p}^{1}=\omega_{1}^{0} \times \boldsymbol{p}^{0}\) is the contribution to point \(P\)’s total velocity by the rotation of the body frame.

Notice that, if \(\boldsymbol{p}^{1}\) is fixed in the moving body frame , then (11) can be further reduced to

\[\dot{\boldsymbol{p}}^{0}=\dot{\boldsymbol{o}}_{1}^{0}+\boldsymbol{\omega}_{1}^{0} \times \boldsymbol{p}^{0}\]