Time Derivative of Rotation Matrices: A Tutorial Shiyu Zhao Abstract— The time derivative of a rotation matrix equals the product of a skew-symmetric matrix and the rotation matrix itself. This article gives a brief tutorial on the well-known result. I. INTRODUCTION The attitude of a ground or aerial robot is often represented by a rotation matrix, whose time derivative is important to characterize the rotational kinematics of the robot. It is a well-known result that the time derivative of a rotation matrix equals the product of a skew-symmetric matrix and the rotation matrix itself. One classic method to derive this result is as follows [1, Sec 4.1], [2, Sec 2.3.1], and [3, Sec 4.2.2] (see [4] for other methods). Let R(t) ∈R3×3 with t ≥0 be a rotation matrix satisfying R(t)RT(t) = I for all t where I is the identity matrix. Taking time derivative on both sides of R(t)RT(t) = I gives ˙R(t)RT(t) + R(t) ˙RT(t) = 0, which indicates that S(t) ≜˙R(t)RT(t) is a skew-symmetric matrix satisfying S(t)+ST(t) = 0 for all t, and consequently ˙R(t) = S(t)R(t). The above derivation is simple, but it is not straightforward to see the precise physical meaning of S(t) (though S(t) corresponds to an angular velocity vector, it is unclear which reference frame this vector is expressed in). This article gives another simple derivation, which is essentially a reorganization of the derivation in [1]–[3], to clarify the precise physical meanings of the quantities in the expression of the time derivative of a rotation matrix. Notation: For any vector w = [w1, w2, w3]T ∈R3, define the skew-symmetric operator [·]× as [w]× ≜   0 −w3 w2 w3 0 −w1 −w2 w1 0  ∈R3×3. (1) The skew-symmetric operator is useful because it can convert a cross product of two vectors into a matrix-vector product. More specifically, for any w, x ∈R3, it can be easily verified that w × x = [w]× x. Another useful property is that for any w ∈R3 and any rotation matrix R ∈R3×3 satisfying RRT = I and det(R) = 1 it holds that [Rw]× = R [w]× RT [3, Section 4.2.1]. Shiyu Zhao is with the Department of Automatic Control and Systems En- gineering, University of Sheffield, UK. szhao@sheffield.ac.uk xA yA zA xB yB zB wB Fig. 1: Frame A is fixed while frame B is rotating. II. TIME DERIVATIVE OF ROTATION MATRICES Consider two reference frames A and B in the three- dimensional space (see Figure 1). Assume the origins of the two frames collocate with each other. Suppose frame A is fixed and frame B is rotating. In the area of robotics, frame A usually corresponds to the world frame fixed on the ground, and frame B usually corresponds to the body frame attached to the body of a robot. In the sequel, the time variables of all the matrices and vectors are omitted for the sake of simplicity. Let the rotation matrix RA B ∈R3×3, which satisfies (RA B)−1 = (RA B)T and det(RA B) = 1, represent the rotational transformation from frame B to frame A. For any point in the space, suppose PA ∈R3 and PB ∈R3 are its coordinates expressed in frames A and B, respectively, then PA = RA BPB. Let RB A = (RA B)T be the rotation from frame A to frame B. Suppose wB ∈R3 is the angular velocity of frame B (relative to frame A) expressed in frame B. The vector wB quantifies the rotational movement of frame B: ∥wB∥equals to the angular rate, which quantifies how fast frame B is rotating, and wB/∥wB∥indicates the axis of the rotational movement. Since the angular velocity is a vector, it can also be expressed in frame A as wA ∈R3, which satisfies wA = RA BwB. The following is the main result on the relation between rotational transformations and angular velocities. Theorem 1 (Time Derivative of Rotation Matrices). The time derivative of the rotational transformations RA B and RB A are expressed as ˙RA B = [wA]×RA B (2) ˙RA B = RA B[wB]× (3) ˙RB A = −RB A[wA]× (4) ˙RB A = −[wB]×RB A (5) arXiv:1609.06088v1 [cs.RO] 20 Sep 2016 Proof. We first prove (2). Consider an arbitrary point fixed in frame B. If PA and PB are the coordinates of this point in frames A and B, respectively, then PB is constant since the point is fixed in frame B, and PA is time-varying since frame B is rotating. As a result, we have ˙PB = 0. Taking time derivative on both sides of PA = RA BPB yields ˙PA = ˙RA BPB. (6) On the other hand, by the relation between linear and angular velocities, we have ˙PA = wA × PA = [wA]×PA. (7) Substituting (7) into (6) gives ˙RA BPB = [wA]×PA = [wA]×RA BPB. (8) Since PB may be arbitrarily chosen, equation (8) holds for arbitrary PB ∈R3 and hence implies (2). Equations (3)–(5) can be derived from (2). In particular, by the property of the skew-symmetric operator, we have [wA]× =  RA BwB  × = RA B [wB]× (RA B)T. (9) Substituting (9) into (2) yields ˙RA B = [wA]× RA B = RA B [wB]× (RA B)TRA B = RA B [wB]×, which is (3). Taking transpose on both sides of (2) gives ˙RB A = −RB A [wA]×, which is (4). By substituting (9) into (4) leads to (5). As indicated by Theorem 1, the expression of the time derivative depends on the definitions of the rotation transfor- mation and angular velocity. One should be clear about their physical meanings before applying (2)–(5). III. PRACTICAL CONSIDERATION IN ROBOTIC MOTION For a robot equipped with an inertial measurement unit (IMU), the value of wB, which is the angular velocity of the robot relative to the world frame expressed in its body frame, can be directly measured. As a result, equations (3) and (5), i.e., ˙RA B = RA B[wB]× ˙RB A = −[wB]×RB A are particularly useful in practice. It must be noted that the origins of frames A and B are assumed to collocate with each other in Theorem 1. This assumption is, however, usually not satisfied for moving robots because the body frame may translate in the space (see Figure 2). Nevertheless, (3) and (5) still holds in this case. To prove that, we may introduce an intermediate frame A′ whose axes are parallel to those of frame A and origin collocates with the origin of frame B. By considering frames A′ and B, we have ˙RA′ B = RA′ B [wB]× and ˙RB A′ = −[wB]×RB A′. Since the axes of frame A′ are parallel to those of frame A, we always have RA′ B = RA B and RB A′ = RB A and consequently (3) and (5) still holds (note wB remain the same). On the other hand, if the origins of frames A and B do not collocate, equations (2) and (4) do not hold any more because w′ A ̸= wA due to the nonzero translation between frames A′ and A. With the above discussion, we A x y z B x y z wB RA B Fig. 2: The world frame A and body frame B for a robot moving in the three-dimensional space. A xA yA B xB yB α Fig. 3: The world frame A and body frame B for a robot moving in the plane. know equations (3) and (5) are more useful than equations (2) and (4) in practice. If a robot is moving in the plane, the rotation (or orien- tation) of the robot can be represented by a single angle α (see Figure 3). Then, the rotation transformation from frame B to frame A is Rα =  cos α −sin α sin α cos α  . In order to verify Rα, one may examine some specific points in frame B such as e1 = [1, 0]T and e2 = [0, 1]T. Taking time derivative on both sides of Rα gives ˙Rα =  −sin α −cos α cos α −sin α  ˙α. (10) Expression (10) may also be obtained as a special case of (3). In particular, we can consider the three-dimensional frame with the z-axes pointing out of the paper in Figure 3. Then, RA B =   cos α −sin α 0 sin α cos α 0 0 0 1  . The angular velocity of the robot can be expressed as wA = wB = ˙αe3 where e3 = [0, 0, 1]T. By applying (2) or (3), it is straightforward to obtain (10). REFERENCES [1] R. M. Murray, Z. Li, and S. S. Sastry, A Mathematical Introduction to Robotic Manipulation. CRC Press, 1994. [2] Y. Ma, S. Soatto, J. Kosecka, and S. Sastry, An Invitation to 3D Vision. New York: Springer, 2004. [3] M. W. Spong, S. Hutchinson, and M. Vidyasagar, Robot Modeling and Control. John Wiley & Sons, Inc., 2006. [4] F. Hamano, “Derivative of rotation matrix - direct matrix derivation of well-known formula,” in Proceedings of Green Energy and Systems Conference, (Long Beach, CA), 2013. Time Derivative of Rotation Matrices: A Tutorial Shiyu Zhao Abstract— The time derivative of a rotation matrix equals the product of a skew-symmetric matrix and the rotation matrix itself. This article gives a brief tutorial on the well-known result. I. INTRODUCTION The attitude of a ground or aerial robot is often represented by a rotation matrix, whose time derivative is important to characterize the rotational kinematics of the robot. It is a well-known result that the time derivative of a rotation matrix equals the product of a skew-symmetric matrix and the rotation matrix itself. One classic method to derive this result is as follows [1, Sec 4.1], [2, Sec 2.3.1], and [3, Sec 4.2.2] (see [4] for other methods). Let R(t) ∈R3×3 with t ≥0 be a rotation matrix satisfying R(t)RT(t) = I for all t where I is the identity matrix. Taking time derivative on both sides of R(t)RT(t) = I gives ˙R(t)RT(t) + R(t) ˙RT(t) = 0, which indicates that S(t) ≜˙R(t)RT(t) is a skew-symmetric matrix satisfying S(t)+ST(t) = 0 for all t, and consequently ˙R(t) = S(t)R(t). The above derivation is simple, but it is not straightforward to see the precise physical meaning of S(t) (though S(t) corresponds to an angular velocity vector, it is unclear which reference frame this vector is expressed in). This article gives another simple derivation, which is essentially a reorganization of the derivation in [1]–[3], to clarify the precise physical meanings of the quantities in the expression of the time derivative of a rotation matrix. Notation: For any vector w = [w1, w2, w3]T ∈R3, define the skew-symmetric operator [·]× as [w]× ≜   0 −w3 w2 w3 0 −w1 −w2 w1 0  ∈R3×3. (1) The skew-symmetric operator is useful because it can convert a cross product of two vectors into a matrix-vector product. More specifically, for any w, x ∈R3, it can be easily verified that w × x = [w]× x. Another useful property is that for any w ∈R3 and any rotation matrix R ∈R3×3 satisfying RRT = I and det(R) = 1 it holds that [Rw]× = R [w]× RT [3, Section 4.2.1]. Shiyu Zhao is with the Department of Automatic Control and Systems En- gineering, University of Sheffield, UK. szhao@sheffield.ac.uk xA yA zA xB yB zB wB Fig. 1: Frame A is fixed while frame B is rotating. II. TIME DERIVATIVE OF ROTATION MATRICES Consider two reference frames A and B in the three- dimensional space (see Figure 1). Assume the origins of the two frames collocate with each other. Suppose frame A is fixed and frame B is rotating. In the area of robotics, frame A usually corresponds to the world frame fixed on the ground, and frame B usually corresponds to the body frame attached to the body of a robot. In the sequel, the time variables of all the matrices and vectors are omitted for the sake of simplicity. Let the rotation matrix RA B ∈R3×3, which satisfies (RA B)−1 = (RA B)T and det(RA B) = 1, represent the rotational transformation from frame B to frame A. For any point in the space, suppose PA ∈R3 and PB ∈R3 are its coordinates expressed in frames A and B, respectively, then PA = RA BPB. Let RB A = (RA B)T be the rotation from frame A to frame B. Suppose wB ∈R3 is the angular velocity of frame B (relative to frame A) expressed in frame B. The vector wB quantifies the rotational movement of frame B: ∥wB∥equals to the angular rate, which quantifies how fast frame B is rotating, and wB/∥wB∥indicates the axis of the rotational movement. Since the angular velocity is a vector, it can also be expressed in frame A as wA ∈R3, which satisfies wA = RA BwB. The following is the main result on the relation between rotational transformations and angular velocities. Theorem 1 (Time Derivative of Rotation Matrices). The time derivative of the rotational transformations RA B and RB A are expressed as ˙RA B = [wA]×RA B (2) ˙RA B = RA B[wB]× (3) ˙RB A = −RB A[wA]× (4) ˙RB A = −[wB]×RB A (5) arXiv:1609.06088v1 [cs.RO] 20 Sep 2016 Proof. We first prove (2). Consider an arbitrary point fixed in frame B. If PA and PB are the coordinates of this point in frames A and B, respectively, then PB is constant since the point is fixed in frame B, and PA is time-varying since frame B is rotating. As a result, we have ˙PB = 0. Taking time derivative on both sides of PA = RA BPB yields ˙PA = ˙RA BPB. (6) On the other hand, by the relation between linear and angular velocities, we have ˙PA = wA × PA = [wA]×PA. (7) Substituting (7) into (6) gives ˙RA BPB = [wA]×PA = [wA]×RA BPB. (8) Since PB may be arbitrarily chosen, equation (8) holds for arbitrary PB ∈R3 and hence implies (2). Equations (3)–(5) can be derived from (2). In particular, by the property of the skew-symmetric operator, we have [wA]× =  RA BwB  × = RA B [wB]× (RA B)T. (9) Substituting (9) into (2) yields ˙RA B = [wA]× RA B = RA B [wB]× (RA B)TRA B = RA B [wB]×, which is (3). Taking transpose on both sides of (2) gives ˙RB A = −RB A [wA]×, which is (4). By substituting (9) into (4) leads to (5). As indicated by Theorem 1, the expression of the time derivative depends on the definitions of the rotation transfor- mation and angular velocity. One should be clear about their physical meanings before applying (2)–(5). III. PRACTICAL CONSIDERATION IN ROBOTIC MOTION For a robot equipped with an inertial measurement unit (IMU), the value of wB, which is the angular velocity of the robot relative to the world frame expressed in its body frame, can be directly measured. As a result, equations (3) and (5), i.e., ˙RA B = RA B[wB]× ˙RB A = −[wB]×RB A are particularly useful in practice. It must be noted that the origins of frames A and B are assumed to collocate with each other in Theorem 1. This assumption is, however, usually not satisfied for moving robots because the body frame may translate in the space (see Figure 2). Nevertheless, (3) and (5) still holds in this case. To prove that, we may introduce an intermediate frame A′ whose axes are parallel to those of frame A and origin collocates with the origin of frame B. By considering frames A′ and B, we have ˙RA′ B = RA′ B [wB]× and ˙RB A′ = −[wB]×RB A′. Since the axes of frame A′ are parallel to those of frame A, we always have RA′ B = RA B and RB A′ = RB A and consequently (3) and (5) still holds (note wB remain the same). On the other hand, if the origins of frames A and B do not collocate, equations (2) and (4) do not hold any more because w′ A ̸= wA due to the nonzero translation between frames A′ and A. With the above discussion, we A x y z B x y z wB RA B Fig. 2: The world frame A and body frame B for a robot moving in the three-dimensional space. A xA yA B xB yB α Fig. 3: The world frame A and body frame B for a robot moving in the plane. know equations (3) and (5) are more useful than equations (2) and (4) in practice. If a robot is moving in the plane, the rotation (or orien- tation) of the robot can be represented by a single angle α (see Figure 3). Then, the rotation transformation from frame B to frame A is Rα =  cos α −sin α sin α cos α  . In order to verify Rα, one may examine some specific points in frame B such as e1 = [1, 0]T and e2 = [0, 1]T. Taking time derivative on both sides of Rα gives ˙Rα =  −sin α −cos α cos α −sin α  ˙α. (10) Expression (10) may also be obtained as a special case of (3). In particular, we can consider the three-dimensional frame with the z-axes pointing out of the paper in Figure 3. Then, RA B =   cos α −sin α 0 sin α cos α 0 0 0 1  . The angular velocity of the robot can be expressed as wA = wB = ˙αe3 where e3 = [0, 0, 1]T. By applying (2) or (3), it is straightforward to obtain (10). REFERENCES [1] R. M. Murray, Z. Li, and S. S. Sastry, A Mathematical Introduction to Robotic Manipulation. CRC Press, 1994. [2] Y. Ma, S. Soatto, J. Kosecka, and S. Sastry, An Invitation to 3D Vision. New York: Springer, 2004. [3] M. W. Spong, S. Hutchinson, and M. Vidyasagar, Robot Modeling and Control. John Wiley & Sons, Inc., 2006. [4] F. Hamano, “Derivative of rotation matrix - direct matrix derivation of well-known formula,” in Proceedings of Green Energy and Systems Conference, (Long Beach, CA), 2013.