Skip to main content
Added details
Source Link
David Hammen
  • 75.3k
  • 5
  • 189
  • 285

The transformation matrices $T_{A\to B}$, $T_{B\to C}$, and $T_{C\to D}$ respectively transform a vector from frame $A$ to frame $B$, from $B$ to $C$, and from $C$ to to $D$. As the reference frames all follow the right hand rule, each of these transformation matrices will inherently represent a proper rotation1 (one that does not involve reflections), i.e., a member of $\operatorname{SO}(3)$. A question arises: What is the transformation matrix from the original frame $A$ to the final frame $D$? The answer is

On the transform of a cross product -- and of a $3\times 3$ skew symmetric matrix

In three dimensional space, a skew symmetric matrix can be represented by a vector $\vec s$ (more correctly, by a pseudovector $\vec s$) that is typically denoted as $\left[\vec s\right]_x$. This is the cross product matrix generated from the vector $\vec s$: $\left[\vec s\right]_x \vec a \equiv \vec s \times \vec a$. If $\vec s = [s_1, s_2, s_3]^T$ then the cross product matrix generated from this vector is

$$\left[\vec s\right]_x = \left[\begin{matrix} \phantom{-}0& -s_3 & \phantom{-}s_2 \\ \phantom{-}s_3& \phantom{-}0 & -s_1 \\ -s_2 & \phantom{-}s_1 & \phantom{-}0 \end{matrix}\right]\tag{5}$$

Generating a pseudovector given a 3x3 skew symmetric matrix is similarly trivial: Simply read off the components of the pseudovector using equation (5).

Given pair of reference frames $X$ and $Y$ in $\mathbb R_3$, a proper (det=1) orthonormal transformation matrix between these frames $T_{X\to Y}$, and a pair of vectors $\vec a_X$ and $\vec b_X$ represented in frame $X$ coordinates, the cross product of the corresponding vectors in frame $Y$ is given by $\left(T_{X\to Y} \vec a_X\right)\times\left(T_{X\to Y} \vec b_X\right)$. This is equal to $T_{X\to Y}(\vec a_X \times \vec b_X)$ as the cross product transforms as does an ordinary vector (given a proper orthogonal transformation matrix). Since this is the case for all $\vec b$, the cross product matrix formed from $\vec a$ transforms as $$T_{X\to Y} [\vec a_X]_x T_{X\to Y}^T = [T_{X\to Y} \vec a_X]_x\tag{6}$$

On the time derivative of a $3x3$ transformation matrix

ThisEquation (4) is a bit of a mess. To clean this up, it will be helpful to take a side track on the nature of the time derivative of a proper orthonormal transformation matrix $T$ (note thee lack of subscripts). That $TT^T=I$ means that time derivative of a real transformation matrix $T$ is antisymmetric as $\frac{dT}{dt} T^T + T\frac{dT^T}{dt} = \dot I = 0$ and $\frac{dT^T}{dt} = \left(\frac{dT}{dt}\right)^T$. This in turn means that there exists skew symmetric matrices $S_L$ and $S_R$ such that $$\dot T = S_L T = T S_R \tag{5}$$$$\dot T = S_L T = T S_R \tag{7}$$

In three dimensional space, a skew symmetric matrix can be represented by a vector $\vec s$ (more correctly, by a pseudovector $\vec s$) that is typically denoted as $\left[\vec s\right]_x$. This is the cross product matrix generated from the vector $\vec s$: $\left[\vec s\right]_x \vec a \equiv \vec s \times \vec a$. If $\vec s = [s_1, s_2, s_3]^T$ then the cross product matrix generated from this vector is

$$\left[\vec s\right]_x = \left[\begin{matrix} \phantom{-}0& -s_3 & \phantom{-}s_2 \\ \phantom{-}s_3& \phantom{-}0 & -s_1 \\ -s_2 & \phantom{-}s_1 & \phantom{-}0 \end{matrix}\right]\tag{6}$$

Generating a pseudovector given a 3x3 skew symmetric matrix is similarly trivial: Simply read off the components of the pseudovector using equation (6).

The transport theorem yields a clue regarding the physical nature of $S_R$: $$\frac{d \vec{q}_Y}{dt} = T_{X\to Y} \left(\frac{d \vec{q}_X}{dt} + \vec{\omega}_{Y\to X:X}\times \vec{q}_X\right)$$ Here, $\vec q$ is some vector quantity in three dimensional Cartesian space ($\mathbb R_3$), $X$ and $Y$ are two reference frames for $\mathbb R_3$ with a common origin with right-handed Cartesian bases, and $\vec{\omega}_{Y\to X:X}$ is the angular velocity of frame $X$ with respect to frame $Y$, expressed in frame $X$ coordinates. The transport theorem results from taking the time derivative of $\vec q_Y = T_{X\to Y} \vec q_X$. This in turn implies that $$\frac{d T_{X\to Y}}{dt} = T_{X\to Y} \left[ \vec{\omega}_{Y\to X:X}\right]_x$$$$\frac{d T_{X\to Y}}{dt} = T_{X\to Y} \left[ \vec{\omega}_{Y\to X:X}\right]_x\tag{8}$$ This means that the skew symmetric matrix $S_R$ in equation (57) is the skew symmetric matrix formed from the angular velocity of frame $X$ with respect to frame $Y$, expressed in frame $X$ coordinates. Given that $S_L = T S_R T^T$ from equation (57), the vector that underlies $S_L$ in equation (57) is $$T_{X\to Y} \vec{\omega}_{Y\to X:X} = \vec{\omega}_{Y\to X:Y}$$ In other words, $S_L$ in equation 5(7) is the skew symmetric matrix formed from the angular velocity of frame $X$ with respect to frame $Y$, expressed in frame $Y$ coordinates.

With the above, equation (4) can be rewritten as $$\begin{aligned} \dot T_{D\to A} \equiv T_{D\to A}\left[\vec{\omega}_{A\to D:D} \right]_x =& \phantom{+\,\,\;}T_{B\to A} \left[\vec{\omega}_{A\to B:B}\right]_x T_{C\to B} T_{D\to C} \\ & + T_{B\to A} T_{C\to B} \left[\vec{\omega}_{B\to C:C}\right]_x T_{D\to C} \\ &+ T_{B\to A} T_{C\to B} T_{D\to C} \left[\vec{\omega}_{D\to C:D}\right]_x \end{aligned}\tag{7}$$$$\begin{aligned} \dot T_{D\to A} \equiv T_{D\to A}\left[\vec{\omega}_{A\to D:D} \right]_x =& \phantom{+\,\,\;}T_{B\to A} \left[\vec{\omega}_{A\to B:B}\right]_x T_{C\to B} T_{D\to C} \\ & + T_{B\to A} T_{C\to B} \left[\vec{\omega}_{B\to C:C}\right]_x T_{D\to C} \\ &+ T_{B\to A} T_{C\to B} T_{D\to C} \left[\vec{\omega}_{D\to C:D}\right]_x \end{aligned}\tag{9}$$ This is still a mess, but the solution is straightforward: Move the intermediate skew symmetric matrices to the right2. This yields $$\begin{aligned} T_{D\to A}\left[ \vec{\omega}_{A\to D:D} \right]_x =& \phantom{+\,\,\;}T_{B\to A} T_{C\to B} T_{D\to C} \left[T_{C\to D} T_{B\to C}\vec{\omega}_{A\to B:B}\right]_x \\ & + T_{B\to A} T_{C\to B} T_{D\to C} \left[T_{C\to D} \vec{\omega}_{B\to C:C}\right]_x \\ &+ T_{B\to A} T_{C\to B} T_{D\to C} \left[\vec{\omega}_{D\to C:D}\right]_x \end{aligned}\tag{8}$$$$\begin{aligned} T_{D\to A}\left[ \vec{\omega}_{A\to D:D} \right]_x =& \phantom{+\,\,\;}T_{B\to A} T_{C\to B} T_{D\to C} \left[T_{C\to D} T_{B\to C}\vec{\omega}_{A\to B:B}\right]_x \\ & + T_{B\to A} T_{C\to B} T_{D\to C} \left[T_{C\to D} \vec{\omega}_{B\to C:C}\right]_x \\ &+ T_{B\to A} T_{C\to B} T_{D\to C} \left[\vec{\omega}_{D\to C:D}\right]_x \end{aligned}\tag{10}$$ Or, more simply, $$\vec{\omega}_{A\to D:D} = T_{C\to D} T_{B\to C}\vec{\omega}_{A\to B:B} + T_{C\to D} \vec{\omega}_{B\to C:C} + \vec{\omega}_{D\to C:D}\tag{9}$$$$\vec{\omega}_{A\to D:D} = T_{C\to D} T_{B\to C}\vec{\omega}_{A\to B:B} + T_{C\to D} \vec{\omega}_{B\to C:C} + \vec{\omega}_{D\to C:D}\tag{11}$$

More to followFootnotes

I'll add more1 A proper 3x3 orthogonal transformation matrix has several key essential properties:

  • For any two columns (or any two rows) $i$ and $j$ of the matrix, the inner product of the vectors extracted from those columns (or rows) is $\delta_{ij}$: +1 if $i=j$, 0 otherwise.
  • The cross product of any two columns $i$ and $j$ of the matrix is either the omitted column $k$ or the negation of that column, depending on whether $ijk$ is an even or odd permutation of 1,2,3.
  • The determinant of the transformation matrix is +1. An improper transformation matrix has a determinant of -1. Such improper transformations can result from transforming between frames that involve a reflection such as a between right handed and left handed coordinate systems.
  • One of the eigenvalues of a proper 3x3 orthonormal matrix will be +1. The product of the other two eigenvalues will also be +1. These other two eigenvalues can be real (in which case they are both +1 or both -1) or can be a complex conjugate pair. Only in the case of the identity matrix are the other two eigenvalues also +1.
  • Except for the identity matrix, the eigenvector corresponding to the +1 eigenvalue represents the axis of rotation. (Any axis can serve as an axis of rotation for the identity matrix as a rotation of zero degrees about any axis results in the identity matrix.)
  • All proper 3x3 orthonormal matrices can be expressed as the matrix exponential of a 3x3 skew symmetric matrix. The matrix exponential of a 3x3 skew symmetric matrix is a proper 3x3 orthonormal matrix.
  • The 3x3 skew symmetric matrices form an algebra, $\mathfrak{so}(3)$. The 3x3 proper orthonormal transformation matrices form a group, $\operatorname{SO}(3)$. The relation via the exponential map between $\mathfrak{so}(3)$ and $\operatorname{SO}(3)$ means these are respectively a Lie algebra and a Lie group.

2 Angular velocity is typically expressed in some body fixed frame because that is the frame in which an observer fixed with respect to this laterthe body observes angular velocity. For example, including referencesa rate gyro rigidly attached to a spacecraft body measures the angular velocity with respect to inertial, expressed in a body-fixed case frame.

References

Gallo, Eduardo. "The SO (3) and SE (3) Lie Algebras of Rigid Body Rotations and Motions and their Application to Discrete Integration, Gradient Descent Optimization, and State Estimation." arXiv preprint arXiv:2205.12572] (2023).
Chapter 4 is relevant to the discussion above.

Zhao, Shiyu. "Time derivative of rotation matrices: A tutorial." arXiv preprint arXiv:1609.06088 (2016).
A short but I neednon-handwaving derivation of equation (8).

International Astronomical Union. "SOFA Tools for Earth Attitude." IAU Standards Of Fundamental Astronomy (2017).
Compared to put this on hold atJPL's SPICE, the IAU SOFA software is easier to use, easier to read, better documented, better maintained, and much more up-to-date.

Engø, Kenth. "On the BCH-formula in so (3)." BIT Numerical Mathematics 41 (2001): 629-632.
The Baker–Campbell–Hausdorff formula relates the exponential maps of two values $X$ and $Y$ to the exponential of a third value: $\exp(X)\exp(Y) = \exp(Z)$. Solving this pointfor $Z$ is in timegeneral non-trivial. The referenced article provides a closed form solution for $X,Y,Z \in \mathfrak{so}(3)$. The link is to the official, paywalled version of the paper. Finding a non-paywalled version is a task left for the reader of this answer.

Iserles, Arieh, et al. "Lie-group methods." Acta numerica 9 (2000): 215-365.
Lie group methods are (IMHO) the correct way to numerically integrate transformation matrices. This huge paper takes a very deep dive down the abstract algebra rabbit hole. As with the above reference, finding a non-paywalled version is a task left for the reader of this answer.

The transformation matrices $T_{A\to B}$, $T_{B\to C}$, and $T_{C\to D}$ respectively transform a vector from frame $A$ to frame $B$, from $B$ to $C$, and from $C$ to to $D$. As the reference frames all follow the right hand rule, each of these transformation matrices will inherently represent a proper rotation (one that does not involve reflections), i.e., a member of $\operatorname{SO}(3)$. A question arises: What is the transformation matrix from the original frame $A$ to the final frame $D$? The answer is

On the time derivative of a $3x3$ transformation matrix

This is a bit of a mess. To clean this up, it will be helpful to take a side track on the nature of the time derivative of a proper orthonormal transformation matrix $T$ (note thee lack of subscripts). That $TT^T=I$ means that time derivative of a real transformation matrix $T$ is antisymmetric as $\frac{dT}{dt} T^T + T\frac{dT^T}{dt} = \dot I = 0$ and $\frac{dT^T}{dt} = \left(\frac{dT}{dt}\right)^T$. This in turn means that there exists skew symmetric matrices $S_L$ and $S_R$ such that $$\dot T = S_L T = T S_R \tag{5}$$

In three dimensional space, a skew symmetric matrix can be represented by a vector $\vec s$ (more correctly, by a pseudovector $\vec s$) that is typically denoted as $\left[\vec s\right]_x$. This is the cross product matrix generated from the vector $\vec s$: $\left[\vec s\right]_x \vec a \equiv \vec s \times \vec a$. If $\vec s = [s_1, s_2, s_3]^T$ then the cross product matrix generated from this vector is

$$\left[\vec s\right]_x = \left[\begin{matrix} \phantom{-}0& -s_3 & \phantom{-}s_2 \\ \phantom{-}s_3& \phantom{-}0 & -s_1 \\ -s_2 & \phantom{-}s_1 & \phantom{-}0 \end{matrix}\right]\tag{6}$$

Generating a pseudovector given a 3x3 skew symmetric matrix is similarly trivial: Simply read off the components of the pseudovector using equation (6).

The transport theorem yields a clue regarding the physical nature of $S_R$: $$\frac{d \vec{q}_Y}{dt} = T_{X\to Y} \left(\frac{d \vec{q}_X}{dt} + \vec{\omega}_{Y\to X:X}\times \vec{q}_X\right)$$ Here, $\vec q$ is some vector quantity in three dimensional Cartesian space ($\mathbb R_3$), $X$ and $Y$ are two reference frames for $\mathbb R_3$ with a common origin with right-handed Cartesian bases, and $\vec{\omega}_{Y\to X:X}$ is the angular velocity of frame $X$ with respect to frame $Y$, expressed in frame $X$ coordinates. The transport theorem results from taking the time derivative of $\vec q_Y = T_{X\to Y} \vec q_X$. This in turn implies that $$\frac{d T_{X\to Y}}{dt} = T_{X\to Y} \left[ \vec{\omega}_{Y\to X:X}\right]_x$$ This means that the skew symmetric matrix $S_R$ in equation (5) is the skew symmetric matrix formed from the angular velocity of frame $X$ with respect to frame $Y$, expressed in frame $X$ coordinates. Given that $S_L = T S_R T^T$ from equation (5), the vector that underlies $S_L$ in equation (5) is $$T_{X\to Y} \vec{\omega}_{Y\to X:X} = \vec{\omega}_{Y\to X:Y}$$ In other words, $S_L$ in equation 5 is the skew symmetric matrix formed from the angular velocity of frame $X$ with respect to frame $Y$, expressed in frame $Y$ coordinates.

With the above, equation (4) can be rewritten as $$\begin{aligned} \dot T_{D\to A} \equiv T_{D\to A}\left[\vec{\omega}_{A\to D:D} \right]_x =& \phantom{+\,\,\;}T_{B\to A} \left[\vec{\omega}_{A\to B:B}\right]_x T_{C\to B} T_{D\to C} \\ & + T_{B\to A} T_{C\to B} \left[\vec{\omega}_{B\to C:C}\right]_x T_{D\to C} \\ &+ T_{B\to A} T_{C\to B} T_{D\to C} \left[\vec{\omega}_{D\to C:D}\right]_x \end{aligned}\tag{7}$$ This is still a mess, but the solution is straightforward: Move the intermediate skew symmetric matrices to the right. This yields $$\begin{aligned} T_{D\to A}\left[ \vec{\omega}_{A\to D:D} \right]_x =& \phantom{+\,\,\;}T_{B\to A} T_{C\to B} T_{D\to C} \left[T_{C\to D} T_{B\to C}\vec{\omega}_{A\to B:B}\right]_x \\ & + T_{B\to A} T_{C\to B} T_{D\to C} \left[T_{C\to D} \vec{\omega}_{B\to C:C}\right]_x \\ &+ T_{B\to A} T_{C\to B} T_{D\to C} \left[\vec{\omega}_{D\to C:D}\right]_x \end{aligned}\tag{8}$$ Or, more simply, $$\vec{\omega}_{A\to D:D} = T_{C\to D} T_{B\to C}\vec{\omega}_{A\to B:B} + T_{C\to D} \vec{\omega}_{B\to C:C} + \vec{\omega}_{D\to C:D}\tag{9}$$

More to follow

I'll add more to this later, including references, but I need to put this on hold at this point in time.

The transformation matrices $T_{A\to B}$, $T_{B\to C}$, and $T_{C\to D}$ respectively transform a vector from frame $A$ to frame $B$, from $B$ to $C$, and from $C$ to to $D$. As the reference frames all follow the right hand rule, each of these transformation matrices will inherently represent a proper rotation1 (one that does not involve reflections), i.e., a member of $\operatorname{SO}(3)$. A question arises: What is the transformation matrix from the original frame $A$ to the final frame $D$? The answer is

On the transform of a cross product -- and of a $3\times 3$ skew symmetric matrix

In three dimensional space, a skew symmetric matrix can be represented by a vector $\vec s$ (more correctly, by a pseudovector $\vec s$) that is typically denoted as $\left[\vec s\right]_x$. This is the cross product matrix generated from the vector $\vec s$: $\left[\vec s\right]_x \vec a \equiv \vec s \times \vec a$. If $\vec s = [s_1, s_2, s_3]^T$ then the cross product matrix generated from this vector is

$$\left[\vec s\right]_x = \left[\begin{matrix} \phantom{-}0& -s_3 & \phantom{-}s_2 \\ \phantom{-}s_3& \phantom{-}0 & -s_1 \\ -s_2 & \phantom{-}s_1 & \phantom{-}0 \end{matrix}\right]\tag{5}$$

Generating a pseudovector given a 3x3 skew symmetric matrix is similarly trivial: Simply read off the components of the pseudovector using equation (5).

Given pair of reference frames $X$ and $Y$ in $\mathbb R_3$, a proper (det=1) orthonormal transformation matrix between these frames $T_{X\to Y}$, and a pair of vectors $\vec a_X$ and $\vec b_X$ represented in frame $X$ coordinates, the cross product of the corresponding vectors in frame $Y$ is given by $\left(T_{X\to Y} \vec a_X\right)\times\left(T_{X\to Y} \vec b_X\right)$. This is equal to $T_{X\to Y}(\vec a_X \times \vec b_X)$ as the cross product transforms as does an ordinary vector (given a proper orthogonal transformation matrix). Since this is the case for all $\vec b$, the cross product matrix formed from $\vec a$ transforms as $$T_{X\to Y} [\vec a_X]_x T_{X\to Y}^T = [T_{X\to Y} \vec a_X]_x\tag{6}$$

On the time derivative of a $3x3$ transformation matrix

Equation (4) is a bit of a mess. To clean this up, it will be helpful to take a side track on the nature of the time derivative of a proper orthonormal transformation matrix $T$ (note thee lack of subscripts). That $TT^T=I$ means that time derivative of a real transformation matrix $T$ is antisymmetric as $\frac{dT}{dt} T^T + T\frac{dT^T}{dt} = \dot I = 0$ and $\frac{dT^T}{dt} = \left(\frac{dT}{dt}\right)^T$. This in turn means that there exists skew symmetric matrices $S_L$ and $S_R$ such that $$\dot T = S_L T = T S_R \tag{7}$$

The transport theorem yields a clue regarding the physical nature of $S_R$: $$\frac{d \vec{q}_Y}{dt} = T_{X\to Y} \left(\frac{d \vec{q}_X}{dt} + \vec{\omega}_{Y\to X:X}\times \vec{q}_X\right)$$ Here, $\vec q$ is some vector quantity in three dimensional Cartesian space ($\mathbb R_3$), $X$ and $Y$ are two reference frames for $\mathbb R_3$ with a common origin with right-handed Cartesian bases, and $\vec{\omega}_{Y\to X:X}$ is the angular velocity of frame $X$ with respect to frame $Y$, expressed in frame $X$ coordinates. The transport theorem results from taking the time derivative of $\vec q_Y = T_{X\to Y} \vec q_X$. This in turn implies that $$\frac{d T_{X\to Y}}{dt} = T_{X\to Y} \left[ \vec{\omega}_{Y\to X:X}\right]_x\tag{8}$$ This means that the skew symmetric matrix $S_R$ in equation (7) is the skew symmetric matrix formed from the angular velocity of frame $X$ with respect to frame $Y$, expressed in frame $X$ coordinates. Given that $S_L = T S_R T^T$ from equation (7), the vector that underlies $S_L$ in equation (7) is $$T_{X\to Y} \vec{\omega}_{Y\to X:X} = \vec{\omega}_{Y\to X:Y}$$ In other words, $S_L$ in equation (7) is the skew symmetric matrix formed from the angular velocity of frame $X$ with respect to frame $Y$, expressed in frame $Y$ coordinates.

With the above, equation (4) can be rewritten as $$\begin{aligned} \dot T_{D\to A} \equiv T_{D\to A}\left[\vec{\omega}_{A\to D:D} \right]_x =& \phantom{+\,\,\;}T_{B\to A} \left[\vec{\omega}_{A\to B:B}\right]_x T_{C\to B} T_{D\to C} \\ & + T_{B\to A} T_{C\to B} \left[\vec{\omega}_{B\to C:C}\right]_x T_{D\to C} \\ &+ T_{B\to A} T_{C\to B} T_{D\to C} \left[\vec{\omega}_{D\to C:D}\right]_x \end{aligned}\tag{9}$$ This is still a mess, but the solution is straightforward: Move the intermediate skew symmetric matrices to the right2. This yields $$\begin{aligned} T_{D\to A}\left[ \vec{\omega}_{A\to D:D} \right]_x =& \phantom{+\,\,\;}T_{B\to A} T_{C\to B} T_{D\to C} \left[T_{C\to D} T_{B\to C}\vec{\omega}_{A\to B:B}\right]_x \\ & + T_{B\to A} T_{C\to B} T_{D\to C} \left[T_{C\to D} \vec{\omega}_{B\to C:C}\right]_x \\ &+ T_{B\to A} T_{C\to B} T_{D\to C} \left[\vec{\omega}_{D\to C:D}\right]_x \end{aligned}\tag{10}$$ Or, more simply, $$\vec{\omega}_{A\to D:D} = T_{C\to D} T_{B\to C}\vec{\omega}_{A\to B:B} + T_{C\to D} \vec{\omega}_{B\to C:C} + \vec{\omega}_{D\to C:D}\tag{11}$$

Footnotes

1 A proper 3x3 orthogonal transformation matrix has several key essential properties:

  • For any two columns (or any two rows) $i$ and $j$ of the matrix, the inner product of the vectors extracted from those columns (or rows) is $\delta_{ij}$: +1 if $i=j$, 0 otherwise.
  • The cross product of any two columns $i$ and $j$ of the matrix is either the omitted column $k$ or the negation of that column, depending on whether $ijk$ is an even or odd permutation of 1,2,3.
  • The determinant of the transformation matrix is +1. An improper transformation matrix has a determinant of -1. Such improper transformations can result from transforming between frames that involve a reflection such as a between right handed and left handed coordinate systems.
  • One of the eigenvalues of a proper 3x3 orthonormal matrix will be +1. The product of the other two eigenvalues will also be +1. These other two eigenvalues can be real (in which case they are both +1 or both -1) or can be a complex conjugate pair. Only in the case of the identity matrix are the other two eigenvalues also +1.
  • Except for the identity matrix, the eigenvector corresponding to the +1 eigenvalue represents the axis of rotation. (Any axis can serve as an axis of rotation for the identity matrix as a rotation of zero degrees about any axis results in the identity matrix.)
  • All proper 3x3 orthonormal matrices can be expressed as the matrix exponential of a 3x3 skew symmetric matrix. The matrix exponential of a 3x3 skew symmetric matrix is a proper 3x3 orthonormal matrix.
  • The 3x3 skew symmetric matrices form an algebra, $\mathfrak{so}(3)$. The 3x3 proper orthonormal transformation matrices form a group, $\operatorname{SO}(3)$. The relation via the exponential map between $\mathfrak{so}(3)$ and $\operatorname{SO}(3)$ means these are respectively a Lie algebra and a Lie group.

2 Angular velocity is typically expressed in some body fixed frame because that is the frame in which an observer fixed with respect to the body observes angular velocity. For example, a rate gyro rigidly attached to a spacecraft body measures the angular velocity with respect to inertial, expressed in a body-fixed case frame.

References

Gallo, Eduardo. "The SO (3) and SE (3) Lie Algebras of Rigid Body Rotations and Motions and their Application to Discrete Integration, Gradient Descent Optimization, and State Estimation." arXiv preprint arXiv:2205.12572] (2023).
Chapter 4 is relevant to the discussion above.

Zhao, Shiyu. "Time derivative of rotation matrices: A tutorial." arXiv preprint arXiv:1609.06088 (2016).
A short but non-handwaving derivation of equation (8).

International Astronomical Union. "SOFA Tools for Earth Attitude." IAU Standards Of Fundamental Astronomy (2017).
Compared to JPL's SPICE, the IAU SOFA software is easier to use, easier to read, better documented, better maintained, and much more up-to-date.

Engø, Kenth. "On the BCH-formula in so (3)." BIT Numerical Mathematics 41 (2001): 629-632.
The Baker–Campbell–Hausdorff formula relates the exponential maps of two values $X$ and $Y$ to the exponential of a third value: $\exp(X)\exp(Y) = \exp(Z)$. Solving this for $Z$ is in general non-trivial. The referenced article provides a closed form solution for $X,Y,Z \in \mathfrak{so}(3)$. The link is to the official, paywalled version of the paper. Finding a non-paywalled version is a task left for the reader of this answer.

Iserles, Arieh, et al. "Lie-group methods." Acta numerica 9 (2000): 215-365.
Lie group methods are (IMHO) the correct way to numerically integrate transformation matrices. This huge paper takes a very deep dive down the abstract algebra rabbit hole. As with the above reference, finding a non-paywalled version is a task left for the reader of this answer.

Source Link
David Hammen
  • 75.3k
  • 5
  • 189
  • 285

However, I am wondering how would one convert the Euler angle derivatives into the angular velocity vector as required to apply the transport theorem? I guess this will also need to take into account the rotation sequence?

Regarding the second question, yes you will need to take into account the rotation sequence as matrix multiplication in general is not commutative (i.e., $AB \ne BA$ in general, but see When is matrix multiplication commutative?). Regarding the first question, consider four frames of reference $A$, $B$, $C$, and $D$, each of which has three orthogonal basis vectors, ordered such that they follow the right hand rule.

Preliminaries

The transformation matrices $T_{A\to B}$, $T_{B\to C}$, and $T_{C\to D}$ respectively transform a vector from frame $A$ to frame $B$, from $B$ to $C$, and from $C$ to to $D$. As the reference frames all follow the right hand rule, each of these transformation matrices will inherently represent a proper rotation (one that does not involve reflections), i.e., a member of $\operatorname{SO}(3)$. A question arises: What is the transformation matrix from the original frame $A$ to the final frame $D$? The answer is

$$T_{A\to D} = T_{C\to D} T_{B\to C} T_{A\to B} \tag{1}$$

Suppose that some (and perhaps all) of these transformations vary with time. Taking the time derivative of (1) results in

$$\dot T_{A\to D} = \dot T_{C\to D} T_{B\to C} T_{A\to B} + T_{C\to D} \dot T_{B\to C} T_{A\to B} + T_{C\to D} T_{B\to C} \dot T_{A\to B}\tag{2}$$

It will be advantageous to look at the transpose of equation (1):

$${T_{A\to D}}^T = T_{D\to A} = \left(T_{C\to D} T_{B\to C} T_{A\to B}\right)^T = T_{B\to A} T_{C\to B} T_{D\to C} \tag{3}$$

Differentiating with respect to time yields

$$\dot T_{D\to A} = \dot T_{B\to A} T_{C\to B} T_{D\to C} + T_{B\to A} \dot T_{C\to B} T_{D\to C} + T_{B\to A} T_{C\to B} \dot T_{D\to C}\tag{4}$$

On the time derivative of a $3x3$ transformation matrix

This is a bit of a mess. To clean this up, it will be helpful to take a side track on the nature of the time derivative of a proper orthonormal transformation matrix $T$ (note thee lack of subscripts). That $TT^T=I$ means that time derivative of a real transformation matrix $T$ is antisymmetric as $\frac{dT}{dt} T^T + T\frac{dT^T}{dt} = \dot I = 0$ and $\frac{dT^T}{dt} = \left(\frac{dT}{dt}\right)^T$. This in turn means that there exists skew symmetric matrices $S_L$ and $S_R$ such that $$\dot T = S_L T = T S_R \tag{5}$$

The subscripts $_L$ and $_R$ denote whether the skew symmetric matrix is to the left or right of the transformation matrix $T$.

In three dimensional space, a skew symmetric matrix can be represented by a vector $\vec s$ (more correctly, by a pseudovector $\vec s$) that is typically denoted as $\left[\vec s\right]_x$. This is the cross product matrix generated from the vector $\vec s$: $\left[\vec s\right]_x \vec a \equiv \vec s \times \vec a$. If $\vec s = [s_1, s_2, s_3]^T$ then the cross product matrix generated from this vector is

$$\left[\vec s\right]_x = \left[\begin{matrix} \phantom{-}0& -s_3 & \phantom{-}s_2 \\ \phantom{-}s_3& \phantom{-}0 & -s_1 \\ -s_2 & \phantom{-}s_1 & \phantom{-}0 \end{matrix}\right]\tag{6}$$

Generating a pseudovector given a 3x3 skew symmetric matrix is similarly trivial: Simply read off the components of the pseudovector using equation (6).

The transport theorem yields a clue regarding the physical nature of $S_R$: $$\frac{d \vec{q}_Y}{dt} = T_{X\to Y} \left(\frac{d \vec{q}_X}{dt} + \vec{\omega}_{Y\to X:X}\times \vec{q}_X\right)$$ Here, $\vec q$ is some vector quantity in three dimensional Cartesian space ($\mathbb R_3$), $X$ and $Y$ are two reference frames for $\mathbb R_3$ with a common origin with right-handed Cartesian bases, and $\vec{\omega}_{Y\to X:X}$ is the angular velocity of frame $X$ with respect to frame $Y$, expressed in frame $X$ coordinates. The transport theorem results from taking the time derivative of $\vec q_Y = T_{X\to Y} \vec q_X$. This in turn implies that $$\frac{d T_{X\to Y}}{dt} = T_{X\to Y} \left[ \vec{\omega}_{Y\to X:X}\right]_x$$ This means that the skew symmetric matrix $S_R$ in equation (5) is the skew symmetric matrix formed from the angular velocity of frame $X$ with respect to frame $Y$, expressed in frame $X$ coordinates. Given that $S_L = T S_R T^T$ from equation (5), the vector that underlies $S_L$ in equation (5) is $$T_{X\to Y} \vec{\omega}_{Y\to X:X} = \vec{\omega}_{Y\to X:Y}$$ In other words, $S_L$ in equation 5 is the skew symmetric matrix formed from the angular velocity of frame $X$ with respect to frame $Y$, expressed in frame $Y$ coordinates.

Angular velocity due to a sequence of time-varying transformations

With the above, equation (4) can be rewritten as $$\begin{aligned} \dot T_{D\to A} \equiv T_{D\to A}\left[\vec{\omega}_{A\to D:D} \right]_x =& \phantom{+\,\,\;}T_{B\to A} \left[\vec{\omega}_{A\to B:B}\right]_x T_{C\to B} T_{D\to C} \\ & + T_{B\to A} T_{C\to B} \left[\vec{\omega}_{B\to C:C}\right]_x T_{D\to C} \\ &+ T_{B\to A} T_{C\to B} T_{D\to C} \left[\vec{\omega}_{D\to C:D}\right]_x \end{aligned}\tag{7}$$ This is still a mess, but the solution is straightforward: Move the intermediate skew symmetric matrices to the right. This yields $$\begin{aligned} T_{D\to A}\left[ \vec{\omega}_{A\to D:D} \right]_x =& \phantom{+\,\,\;}T_{B\to A} T_{C\to B} T_{D\to C} \left[T_{C\to D} T_{B\to C}\vec{\omega}_{A\to B:B}\right]_x \\ & + T_{B\to A} T_{C\to B} T_{D\to C} \left[T_{C\to D} \vec{\omega}_{B\to C:C}\right]_x \\ &+ T_{B\to A} T_{C\to B} T_{D\to C} \left[\vec{\omega}_{D\to C:D}\right]_x \end{aligned}\tag{8}$$ Or, more simply, $$\vec{\omega}_{A\to D:D} = T_{C\to D} T_{B\to C}\vec{\omega}_{A\to B:B} + T_{C\to D} \vec{\omega}_{B\to C:C} + \vec{\omega}_{D\to C:D}\tag{9}$$

More to follow

I'll add more to this later, including references, but I need to put this on hold at this point in time.