3D angular velocity and Rodrigues' formula

3D angular velocity and Rodrigues' formula

One type of motion that people often encounter in robotics is the rotation of a rigid body about a fixed axis. Consider a 3D object rotating about an axis $u$ (represented by a unit vector in $R^3$) at a rate of $\theta$ radians per second (rad/s, in $R$) for $t$ seconds. Let $p$ be a point attached to the object and $\dot{p}$ the tangent velocity at point $p$.

An illustration is shown in the cover figure, in which we use $\omega=\theta u$ instead to represent the axis and angle in a unified vectorial form. In the literature, $\omega$ is often named angular velocity.

Angular velocity and exponential map

Let $A$ be an arbitrary point on the axis of rotation and let’s define a Cartesian coordinate frame at $A$, as shown in the cover figure. For simplicity, we express everything under frame $A$ and append an upperscript to the vectors $^Au$, $^Ap$, and $^A\dot{p}$. From the fact that $v=2\pi r/t = \omega r$ in 1D we can verify the following relation
$$
^A\dot{p}(t) = \theta ^Au\times ^Ap(t),
$$
where $\times$ denotes cross product. The above equation is a time-invariant linear differential equation which may be integrated to give
$$
^Ap(t) = \exp\left(t\theta {^Au}\times\right) {^Ap}(0),
$$
where $e^{t\theta {^Au}\times}$ is the exponential map of $t\theta ^Au\times$. The above equation means that if the object rotates about the axis $^Au$ at rate $\theta$ (rad/s) for $t$ seconds, the rotation is given by
$$
R(^Au, \theta, t) = e^{t\theta {^Au}\times} \label{eq:exp-map}
$$

Definition (3D angular velocity). The 3D angular velocity is represented by a coordinate vector expressed in frame $A$, as the product of the angle $\theta\in\mathbb{R}$ and the rotation axis $^Au\in\mathbb{R}^3$:
$$
^A\omega = \theta ^Au.
$$
In constrast, we have $^Au={^A\omega}/ \lVert{^A\omega}\rVert$ and $\theta = \lVert^A\omega\rVert$.

With the definition of angular velocity we can rewrite the exponential map $e^{t\theta ^Au\times}$ by its power series:

\begin{equation} R(^A\omega, t) = I + t^A\omega\times + \frac{\left(t^A\omega\times\right)^2}{2} + \frac{\left(t^A\omega\times\right)^3}{3} + ... = \sum_{n=0}^{\infty}{\frac{1}{n!}\left(t^A\omega\times\right)^n} \label{eq:exp-map-power-series} \end{equation}

Rodrigues’ formula

In this part, we show that the power series accept a closed-form expression, aka the Rodrigues’ formula. From the definition of cross product it is easy to see that the matrix $^A\omega\times$ is a skew-symmetric matrix, i.e. $^A\omega\times \in so(3)$, where $so(3)$ is the vector space of $3\times 3$ skew-symmetric matrices defined by

\begin{equation} so(3) = \left\{ S\in \mathbb{R}^{3\times 3} \mid S^T = -S \right\} \end{equation}

or equivalently

\begin{equation} so(3) = \left\{ \begin{pmatrix} 0 & -\omega_3 & \omega_2\\ \omega_3 & 0 & -\omega_1\\ -\omega_2 & \omega_1 & 0 \end{pmatrix} \mid \left(\omega_1,\omega_2,\omega_3\right) \in R^3 \right\}. \end{equation}

Lemma. Given $\omega\in so(3)$, the following relations hold:

\begin{align} \left(\omega\times\right)^2 &= \omega\omega^T - \|\omega\|^2I, \\ \left(\omega\times\right)^3 &= -\|\omega\|^2 \omega\times, \end{align}

and higher powers of $\omega\times$ can be calculated recursively.

Applying this lemma with $a=t^A\omega$, the exponential map power series become:

\begin{align} R(^A\omega, t) = I + \frac{^A\omega\times}{\|^A\omega\|}\sin\left(\|^A\omega\|t\right) + \frac{\left(^A\omega\times\right)^2}{\|^A\omega\|^2}\left(1-\cos\left(\|^A\omega\|t\right)\right), \label{eq:rodrigues-fomula} \end{align}

This Rodrigues’ formula provides an efficient way of computing the exponential map $e^{t ^A\omega \times}$.

Exponential map is an application from so(3) to SO(3)

Finally, we show that the exponential map transforms skew-symmetric matrices into rotation matrices. In other words, exponentials of $so(3)$ elements are elements in the special orthogonal group defined by

\begin{equation} SO(3) = \left\{ R \in \mathbb{R}^{3\times 3} \mid RR^T = R^TR = I,\ det(R)=+1 \right\}, \end{equation}

or equivalently

\begin{equation} SO(3) = \left\{ r: \mathbb{E}^3 \rightarrow \mathbb{E}^3 \mid \forall x,y\in\mathbb{E}^3,\ \|r(x)-r(y)\|=\|x-y\|,\ g(0)=0\right\}, \end{equation}

Proposition. Given a skew-symmetric matrix $\omega\times \in so(3)$, we have
$$
e^{\omega\times}\in SO(3).
$$
Proof. The following chain of equalities can be checked using Rodrigues’ formula:

\begin{align} \left(e^{\omega\times}\right)^{-1} = e^{-\omega\times} = e^{\omega\times^T} = \left(e^{\omega\times}\right)^T, \end{align}

Thus $\left(e^{\omega\times}\right)^Te^{\omega\times}=I$, from which it follows that $\det\left(e^{\omega\times}\right)= \pm1$ for all $\omega\times\in so(3)$. Using the continuity of the determinant as a function of the entries of a matrix, combined with continuity of the exponential map and the fact that $\det\exp(0) = 1$, we conclude that $\det\left(e^{\omega\times}\right)= +1$.

According to the Rodrigues’ formula it is obvious that the exponential map is not injective, since the norm $\lVert{\omega}\rVert t$ can be chosen modulo $2\pi$ to obtain the same rotation matrix.

Canonical exponential coordinates

It can be shown that the exponential map $\omega \in so(3)\rightarrow e^{\omega\times} \in SO(3)$ is surjective (onto), that is to say, that the exponential map generates the entire group of $SO(3)$: $\forall R\in SO(3)$, there exists $\omega\in\mathbb{R}^3$ such that $R=e^{\omega\times}$. The proof is done by building the reciprocal, called the logarithm map. Details can be found in the book of Murray [1], page 29.

The surjectivity guarantees that any rotation matrix in $SO(3)$ can be generated by taking the exponential of an angular velocity in $\mathbb{R}^3$. The $SO(3)$ group can therefore be represented, or parameterized using $\mathbb{R}^3$. This sort of parameterization is called the canonical exponential coordinates.

Understanding angular velocity in two ways

The 3D vector $\omega=u\theta$ with $|u|=1$ can be understood in two different aspects:

  • On the one hands, $\omega$ represents the anglar velocity of a rigid body rotating around the axis $u$ at rate $\theta$. For a rotation at constant rate $\theta$, the rotation matrix at time $t$ w.r.t. the initial position at time $0$, i.e. $R(u\theta, t)$, is given by the Rodrigues’ formula.
  • On the other hand, $\omega$ represents the net rotation $R(u,\theta)$ about a fixed axis $u=\frac{\omega}{|\omega|}$ through an angle $\theta=|\omega|$.

Reference

  1. Murray, Richard M., et al. A mathematical introduction to robotic manipulation. CRC press, 1994.

Comments