Educational Material

2.4 Attitude Transformations

Since there is not a "standard" attitude representation, the technique chosen is highly dependent upon the specific application. However, the optimal method for a specific application may be different from the desired final representation of the orientation. Therefore, a conversion or transformation between the different attitude representations is needed. Below are some of the more common transformations used that are based on the VectorNav quaternion notation in which $q_4$ is the scalar term.

Quaternion to/from Direction Cosine Matrix

The elements of the DCM can be determined from the associated quaternion using Equation \ref{eq:q2dcm}:

\begin{equation}\label{eq:q2dcm} C= \begin{bmatrix} q_4^2+q_1^2-q_2^2-q_3^2 & 2(q_1q_2+q_3q_4) & 2(q_1q_3-q_2q_4)\\ 2(q_1q_2-q_3q_4) & q_4^2-q_1^2+q_2^2-q_3^2 & 2(q_2q_3+q_1q_4)\\ 2(q_1q_3+q_2q_4) & 2(q_2q_3-q_1q_4) & q_4^2-q_1^2-q_2^2+q_3^2 \end{bmatrix}\end{equation}



There are a variety of ways to extract the quaternion from the DCM defined in Equation \ref{eq:q2dcm}, though several of them contain divide by zero singularities for certain attitudes. A numerically stable method for calculating the quaternion starts with calculating the squares of each quaternion term:

\begin{equation}\begin{split}q_1^2 &=\frac{1}{4}{(1+C_{11}-C_{22}-C_{33})}\\q_2^2 &=\frac{1}{4}{(1-C_{11}+C_{22}-C_{33})}\\q_3^2 &=\frac{1}{4}{(1-C_{11}-C_{22}+C_{33})}\\q_4^2 &=\frac{1}{4}{(1+C_{11}+C_{22}+C_{33})}\\\end{split}\label{eq:dcm2q}\end{equation}

Taking the square root of the maximum value amongst those terms provides the particular value for that term. The remaining terms can be computed using the appropriate formula from Equation \ref{eq:dcm2q2}.

\begin{equation}\label{eq:dcm2q2} \boldsymbol{q} = \frac{1}{4q_1}\begin{bmatrix} 4q_1^2\\ C_{12}+C_{21}\\ C_{31}+C_{13}\\ C_{23}-C_{32} \end{bmatrix} = \frac{1}{4q_2}\begin{bmatrix} C_{12}+C_{21}\\ 4q_2^2\\ C_{23}+C_{32}\\ C_{31}-C_{13} \end{bmatrix} = \frac{1}{4q_3}\begin{bmatrix} C_{31}+C_{13}\\ C_{23}+C_{32}\\ 4q_3^2\\ C_{12}-C_{21} \end{bmatrix} = \frac{1}{4q_4}\begin{bmatrix} C_{23}-C_{32}\\ C_{31}-C_{13}\\ C_{12}-C_{21}\\ 4q_4^2 \end{bmatrix}\end{equation}



While the quaternion has more elements than the minimum required number of parameters for representing attitude, it offers the advantage that when moving from the DCM to the quaternion and back, only algebraic operations---no trigonometric operations---are required for conversion.



Euler Angles to/from Direction Cosine Matrix

The elements of the DCM can be determined from the associated Euler angles, though the precise equation depends on the particular Euler angle sequence (i.e. order of the rotations). The DCM for any Euler angle sequence can be constructed from the individual axis rotations presented in Equation \ref{eq:1axrot}, where the subscripts 1, 2, & 3 denote the axis about which the rotation is made (not the order of rotation).

\begin{equation}\label{eq:1axrot} R_1(\phi) = \begin{bmatrix}1 & 0 & 0\\0 & \cos\phi & \sin\phi \\ 0 & -\sin\phi & \cos\phi \end{bmatrix} \quad R_2(\theta) = \begin{bmatrix}\cos\theta & 0 & -\sin\theta\\0 & 1 & 0 \\ \sin\theta & 0 & \cos\theta \end{bmatrix} \quad R_3(\psi) = \begin{bmatrix}\cos\psi & \sin\psi & 0\\-\sin\psi & \cos\psi & 0 \\ 0 & 0 & 1 \end{bmatrix} \quad\end{equation}



For the standard (3-2-1) set of Euler angles corresponding to yaw-pitch-roll ($\psi$-$\theta$-$\phi$), the DCM is determined using Equation \ref{eq:eul2dcm} ($\cos\phi$ and $\sin\phi$ have been abbreviated $\mbox{c}\phi$ and $\mbox{s}\phi$, respectively). As seen in that equation, the individual rotation matrices $R$ are combined according to the order of the Euler angle sequence, starting on the right and moving left.

\begin{equation}\label{eq:eul2dcm} C_{(3-2-1)} = R_1(\phi)R_2(\theta)R_3(\psi) = \begin{bmatrix}\mbox{c}\theta \mbox{c}\psi & \mbox{c}\theta \mbox{s}\psi & -\mbox{s}\theta\\\mbox{s}\phi \mbox{s}\theta \mbox{c}\psi-\mbox{c}\phi \mbox{s}\psi & \mbox{s}\phi \mbox{s}\theta \mbox{s}\psi + \mbox{c}\phi \mbox{c}\psi & \mbox{s}\phi \mbox{c}\theta\\\mbox{c}\phi \mbox{s}\theta \mbox{c}\psi + \mbox{s}\phi \mbox{s}\psi& \mbox{c}\phi \mbox{s}\theta \mbox{s}\psi - \mbox{s}\phi \mbox{c}\psi & \mbox{c}\phi \mbox{c}\theta\end{bmatrix}\end{equation}



Extracting Euler angles from the DCM varies depending on the particular Euler angle sequence. The (3-2-1) set of Euler angles corresponding to yaw-pitch-roll ($\psi$-$\theta$-$\phi$) is determined using the Equation \ref{eq:dcm2e}.

\begin{equation}\begin{split}\psi=&\tan^{-1}\frac{C_{12}}{C_{11}}\\\theta=&-\sin^{-1}C_{13}\\\phi=&\tan^{-1}\frac{C_{23}}{C_{33}}\end{split}\label{eq:dcm2e}\end{equation}



For the special case where the attitude consists entirely of small-angle rotations, where small is defined as <5°, the DCM only differs from the identity matrix by small quantities, as seen in Equation \ref{eq:dcmsa}. By removing any trigonometric operations in the transformation, this equation is useful both for high-rate control loops and deriving sensitivities to attitude for various filters. Great care must be taken when using this approach to ensure the small angle assumption is not violated.

\begin{equation} \label{eq:dcmsa}C\approx\left[\begin{matrix}1&\psi&-\theta\\-\psi&1&\phi\\\theta&-\phi&1\end{matrix}\right] \end{equation}



Quaternion to/from Euler

A set of Euler angles is most easily determined from the quaternion through a series of two steps utilizing the transformations above. The quaternion are first transformed into a DCM using Equation \ref{eq:q2dcm}. This DCM is then converted into a set of Euler angles with the transformation in Equation \ref{eq:dcm2e}.

Similarly, the quaternion is most easily computed from a set of Euler angles using a two-step process. First, the set of Euler angles is transformed into a DCM using Equation \ref{eq:eul2dcm}. Equations \ref{eq:dcm2q} and \ref{eq:dcm2q2} are then used to convert the DCM into the associated quaternion.

Attitude Kinematics

The attitude kinematic differential equation relates the time derivative of the attitude representation with the associated angular rate, $\boldsymbol{\omega}$ (eg. as measured by a gyroscope). Each attitude representation can be written in terms of a kinematic differential equation.

The time rate of change of the DCM ($[\dot{C}]$) is given by Equation \ref{eq:dcmak}. The time rate of change of the quaternion ($\dot{\boldsymbol{q}}$) is given by Equation \ref{eq:quatak}. Finally, the time rate of change of yaw-pitch-roll ($\dot{\psi}$-$\dot{\theta}$-$\dot{\phi}$) is given by Equation \ref{eq:eaak}. Note that this equation reveals that yaw rate, roll rate, and pitch rate are not equal to the angular rate measured by a gyro. Furthermore, Equation \ref{eq:eaak} reveals an additional singularity associated with Euler angles, in this case when $\cos\theta = 0$.

\begin{equation} \label{eq:dcmak} [\dot{C}]=-\begin{bmatrix}0 & -\omega_3 & \omega_2\\ \omega_3 & 0 & -\omega_1 \\ -\omega_2 & \omega_1 & 0 \end{bmatrix}[C]\end{equation}

\begin{equation} \label{eq:quatak} \left(\begin{matrix} \dot{q}_1\\ \dot{q}_2\\ \dot{q}_3\\ \dot{q}_4\end{matrix} \right)= \frac{1}{2}\left[\begin{matrix} q_1&q_4&-q_3&q_2\\ q_2&q_3&q_4&-q_1\\ q_3&-q_2&q_1&q_4\\ q_4&-q_1&-q_2&-q_3 \end{matrix}\right] \left( \begin{matrix}0\\ \omega_1\\ \omega_2\\ \omega_3 \end{matrix}\right) \end{equation}

\begin{equation} \label{eq:eaak}\left(\begin{matrix}\dot{\psi}\\\dot{\theta}\\\dot{\phi}\end{matrix}\right)=\frac{1}{\cos\theta}\left[\begin{matrix}0&\sin\phi&\cos\phi\\0&\cos\phi\cos\theta&-\sin\phi\cos\theta\\\cos\theta&\sin\phi\sin\theta&\cos\phi\sin\theta\end{matrix}\right]\left(\begin{matrix}\omega_1\\\omega_2\\\omega_3\end{matrix}\right)\end{equation}