Skip to content

Special Orthogonal and Special Euclidean Groups

Definition

Lie summary Lie summary

Figure 1 Relationship between Lie group and Lie algebra

\(SO(3)\) is a Lie group that consists of orthogonal matrices (orthonormal rows and columns) that provide distance-preserving transformations of a Euclidean space. \(SE(3)\) is a Lie group that represents poses.

Group Properties Special Orthogonal Group Special Euclidean Group
Lie Group \(SO(3) = \left\{ \mathbf{R} \in \mathbb{R}^{3 \times 3} \ \| \ \mathbf{R} \mathbf{R}^T = \mathbf{R}^T \mathbf{R} = \mathbf{I}, \ \text{det}(\mathbf{R}) = 1 \right\}\) \(SE(3) = \left\{ \mathbf{T} = \left[ \begin{array}{cc} \mathbf{R} & \mathbf{t} \\\mathbf{0}^T & 1 \end{array} \right] \in \mathbb{R}^{4 \times 4} \ \big\| \ \mathbf{R} \in SO(3), \ \mathbf{t} \in \mathbb{R}^3 \right\}\)
Inverse \(\mathbf{R}^{-1} = \mathbf{R}^T \in SO(3)\) \(\begin{align*} \mathbf{T}^{-1} = \left[ \begin{array}{cc} \mathbf{R}^T & -\mathbf{R}^T \mathbf{t} \\ \mathbf{0}^T & 1 \end{array} \right] \in SE(3) \end{align*}\)
Lie Algebra Set of skew-symmetrics matrices, \(\left[ \boldsymbol{\rho} \right]_\times\) with \(\boldsymbol{\rho} \in \mathbb{R}^3\) \(\begin{align*} \text{Vector space: } &\mathfrak{so}(3) = \left\{ \boldsymbol{P} = \left[ \boldsymbol{\rho} \right]_{\times} \in \mathbb{R}^{3 \times 3} \ \| \ \boldsymbol{\rho} \in \mathbb{R}^3 \right\} \\ \text{Field: } &\mathbb{R} \\ \text{Lie bracket: } &\left[ \boldsymbol{P}_1, \boldsymbol{P}_2 \right] = \boldsymbol{P}_1 \boldsymbol{P}_2 - \boldsymbol{P}_2 \boldsymbol{P}_1. \end{align*}\) \(\begin{align*} \text{Vector space: } &\mathfrak{se}(3) = \left\{ \boldsymbol{\Xi} = \left[ \boldsymbol{\xi} \right]_\times \in \mathbb{R}^{4 \times 4} \ \| \ \boldsymbol{\xi} \in \mathbb{R}^6 \right\} \\ \text{Field: } &\mathbb{R} \\ \text{Lie bracket: } &\left[\boldsymbol{\Xi}_1, \boldsymbol{\Xi}_2 \right] = \boldsymbol{\Xi}_1 \boldsymbol{\Xi}_2 - \boldsymbol{\Xi}_2 \boldsymbol{\Xi}_1, \\ \end{align*}\) where \(\begin{align*} \boldsymbol{\xi} = \left[ \begin{array}{c} \boldsymbol{\ell} \\ \boldsymbol{\rho} \end{array} \right] \in \mathbb{R}^{6}, \ \boldsymbol{\ell}, \boldsymbol{\rho} \in \mathbb{R}^3, \ \left[ \boldsymbol{\xi} \right]_\times = \left[ \begin{array}{cc} \left[ \boldsymbol{\rho} \right]_\times & \boldsymbol{\ell} \\ \mathbf{0}^T & 0 \end{array} \right] \in \mathbb{R}^{4 \times 4}, \\ \end{align*}\) \(\boldsymbol{\ell}\) is the "translation part" (note that this is different from the translation in the matrix), \(\boldsymbol{\rho}\) is the rotation part. Here \(\left[ \ \cdot \ \right]_\times\) has an extended meaning since in \(\mathfrak{se}(3)\), a six-dimensional vector is converted to a four-dimensional matrix using the \(\left[ \ \cdot \ \right]_\times\) operator, but it is no longer a skew-symmetric matrix. However, the meaning is still "vector-to-matrix" operation
Exponential Map \(\begin{align*} \mathbf{R} = e^{\left[\boldsymbol{\rho} \right]_\times} &= e^{ \left[ \theta \hat{\mathbf{e}} \right]_\times} = \sum^{\infty}_{k = 0} \frac{1}{k!} \left(\theta \left[\hat{\mathbf{e}} \right]_\times \right)^k \\ &= \mathbf{I} + \theta \left[ \hat{\mathbf{e}} \right]_\times + \frac{\theta^2}{2} \left[ \hat{\mathbf{e}} \right]^2_\times + \frac{\theta^3}{3!} \left[ \hat{\mathbf{e}} \right]^2_\times + \ldots \\ &= \mathbf{I} + \left( \theta - \frac{\theta^3}{3!} + \ldots \right) \left[ \hat{\mathbf{e}} \right]_\times + \left( \frac{\theta^2}{2} - \frac{\theta^4}{4!} + \ldots \right) \left[ \hat{\mathbf{e}} \right]^2_\times \\ &= \mathbf{I} + \sin \theta \left[ \hat{\mathbf{e}} \right]_\times + \left(1 - \cos \theta \right) \left[ \hat{\mathbf{e}} \right]^2_\times \\ &= \cos \theta \mathbf{I} + \left(1 - \cos \theta \right) \hat{\mathbf{e}} \hat{\mathbf{e}}^T + \sin \theta \left[ \hat{\mathbf{e}} \right]_\times \end{align*}\) \(\begin{align*} \mathbf{T} = \exp \left\{ \boldsymbol{ \left[\xi \right]_\times} \right\} &= \sum^\infty_{n = 0} \frac{1}{n!} \left[\boldsymbol{\xi} \right]^n_\times \\ \mathbf{e}^{\left[ \boldsymbol{\xi} \right]_\times} &= \sum^\infty_{n = 0} \frac{1}{n!} \left(\left[ \boldsymbol{\xi} \right]_\times \right)^n \\ &= \sum^\infty_{n = 0} \frac{1}{n!} \left( \left[ \begin{array}{c} \boldsymbol{\ell} \\ \boldsymbol{\rho} \end{array} \right]_\times \right)^n \\ &= \sum^\infty_{n = 0} \frac{1}{n!} \left[ \begin{array}{cc} \left[\boldsymbol{\rho} \right]_\times & \boldsymbol{\ell} \\ \mathbf{0}^T & 0 \end{array} \right]^n \\ &= \left[ \begin{array}{cc} \sum^{\infty}_{n = 0} \frac{1}{n!} \left( \left[ \boldsymbol{\rho} \right]_\times \right)^n & \left(\sum^{\infty}_{n = 0} \frac{1}{(n + 1)!} \left( \left[ \boldsymbol{\rho} \right]_\times \right)^n \right) \boldsymbol{\ell} \\ \mathbf{0}^T & 1 \end{array} \right] \\ &\triangleq \underbrace{ \left[ \begin{array}{cc} \mathbf{R} & \mathbf{J} \boldsymbol{\ell} \\ \mathbf{0}^T & 1 \end{array} \right]}_\mathbf{T} \in SE(3), \end{align*}\)
Jacobian The Jacobian plays an important role in allowing us to convert the translation component of pose in \(\mathfrak{se}(3)\) into the translation component of pose in \(SE(3)\) through \(\mathbf{t} = \mathbf{J} \boldsymbol{\ell}\). Let \(\boldsymbol{\rho} = \theta \hat{\mathbf{e}}\). Then we can obtain closed-form solutions for the left Jacobian matrix \(\mathbf{J}\) and its inverse \(\begin{align*} \mathbf{J}_l &\triangleq \sum^{\infty}_{n = 0} \frac{1}{(n + 1)!} \left( \left[ \boldsymbol{\rho} \right]_\times \right)^n \\ &= \mathbf{I} + \frac{1}{2!}\theta \left[ \hat{\mathbf{e}} \right]_\times + \frac{1}{3!}\theta^2 \left[ \hat{\mathbf{e}} \right]^2_\times + \frac{1}{4!}\theta^3 \left[ \hat{\mathbf{e}} \right]^3_\times \ldots \\ &= \frac{1}{\theta} \left( \frac{1}{2!}\theta^2 - \frac{1}{4!}\theta^4 \ldots \right) \left[ \hat{\mathbf{e}} \right]_\times + \frac{1}{\theta} \left(\frac{1}{3!} \theta^3 - \frac{1}{5}\theta^5 + \ldots \right) \left[ \hat{\mathbf{e}} \right]^2_\times + \mathbf{I} \\ &= \frac{1}{\theta} (1 - \cos \theta) \left[ \hat{\mathbf{e}} \right]_\times + \frac{\theta - \sin \theta}{\theta} (\hat{\mathbf{e}} \hat{\mathbf{e}}^T - \mathbf{I}) + \mathbf{I} \\ &= \frac{\sin \theta}{\theta} \mathbf{I} + \left(1 - \frac{\sin \theta}{\theta} \right) \hat{\mathbf{e}} \hat{\mathbf{e}}^T + \frac{1 - \cos \theta}{\theta} \left[ \hat{\mathbf{e}} \right]_\times \\ \mathbf{J}^{-1}_l &\triangleq \frac{\theta}{2} \cot \frac{\theta}{2} \mathbf{I} + \left(1 - \frac{\theta}{2} \cot \frac{\theta}{2} \right) \hat{\mathbf{e}} \hat{\mathbf{e}}^T - \frac{\theta}{2} \left[ \hat{\mathbf{e}} \right]_\times \\ \mathbf{R} &= \mathbf{I} + \left[ \boldsymbol{\rho} \right]_\times \mathbf{J}_l. \end{align*}\)
The left and right Jacobians are related as
\(\begin{align*} \mathbf{J}_l (\boldsymbol{\rho}) = \mathbf{R} \mathbf{J}_r (\boldsymbol{\rho}) \\ \mathbf{J}_r (\boldsymbol{\rho}) = \mathbf{J}_l (-\boldsymbol{\rho}) \end{align*}\)
The left and right Jacobians of \(SE(3)\) are
\(\begin{align*} \boldsymbol{\mathcal{J}}_r \left(\boldsymbol{\xi} \right) &= \left[ \begin{array}{cc} \mathbf{J}_r & \mathbf{Q}_r \\ \mathbf{0} & \mathbf{J}_r \end{array} \right] \\ \boldsymbol{\mathcal{J}}_l \left(\boldsymbol{\xi} \right) &= \left[ \begin{array}{cc} \mathbf{J}_l & \mathbf{Q}_l \\ \mathbf{0} & \mathbf{J}_l \end{array} \right]. \end{align*}\)
See Barfoot \((8.91)\) for definition
Jacobian Properties Per the derivative definitions, the right Jacobian of \(SO(3)\) has the following properties, for any \(\boldsymbol{\theta}\) and small \(\delta \boldsymbol{\theta}\):

\(\begin{align*} \exp \left[\boldsymbol{\theta} + \delta \boldsymbol{\theta} \right]_\times &\approx \exp \left[\boldsymbol{\theta} \right]_\times \exp \left[\mathbf{J}_r(\boldsymbol{\theta}) \delta \boldsymbol{\theta} \right]_\times \\ \exp \left[\boldsymbol{\theta} \right]_\times \exp \left[ \delta \boldsymbol{\theta} \right]_\times &\approx \exp \left[ \boldsymbol{\theta} + \mathbf{J}^{-1}_r (\boldsymbol{\theta}) \delta \boldsymbol{\theta} \right]_\times \\ \left[ \ln \left( \exp \left[ \boldsymbol{\theta} \right]_\times \exp \left[ \delta \boldsymbol{\theta} \right]_\times \right) \right]_{-\times} &\approx \boldsymbol{\theta} + \mathbf{J}^{-1}_r (\boldsymbol{\theta}) \delta \boldsymbol{\theta} \end{align*}\)
Logarithm Map \(\begin{align*} \theta &= \arccos \left( \frac{\text{tr}(\mathbf{R}) - 1}{2} \right) \\ \ln (\mathbf{R}) &= \frac{\theta}{2 \sin \theta} \left( \mathbf{R} - \mathbf{R}^T \right) \\ \boldsymbol{\rho} &= \left[ \ln \left( \mathbf{R} \right) \right]_{-\times} \end{align*}\) \(\begin{align*} \boldsymbol{\xi} &= \left[ \ln \left( \mathbf{T} \right) \right]_{-\times} \\ \boldsymbol{\ell} &= \mathbf{J}^{-1} \mathbf{t} \end{align*}\)
Adjoint The adjoint of a Lie group is a way of describing the elements of that group as linear transformations of its Lie algebra, which is a vector space. For \(SO(3)\), the adjoint representation is the same as the group itself \(\text{Adj}_{\mathbf{R}} = \mathbf{R}.\) Then we have
\(\begin{align*} &\mathbf{R} \ \exp \left( \left[ \boldsymbol{\rho} \right]_\times \right) = \exp \left( \text{Adj}_{\mathbf{R}} \cdot \left[ \boldsymbol{\rho} \right]_\times \right) \mathbf{R} \ \Rightarrow \\ &\exp \left( \text{Adj}_{\mathbf{R}} \cdot \left[ \boldsymbol{\rho} \right]_\times \right) = \mathbf{R} \ \exp \left( \left[ \boldsymbol{\rho} \right]_\times \right) \mathbf{R}^{-1}. \end{align*}\)
In order words, rotating a tangent vector by an element "moves" it from the tangent space on the right side of the element to the tangent space on the left
The adjoint map of \(SE(3)\) transforms an element \(\left[ \mathbf{x} \right]_{\times} \in \mathfrak{se}(3)\) to another element of \(\mathfrak{se}(3)\) via conjugation \(\text{Ad}_{\mathbf{T}} \left[ \mathbf{x} \right]_\times = \mathbf{T} \left[ \mathbf{x} \right]_\times \mathbf{T}^{-1} = \left[\boldsymbol{\mathcal{T}} \mathbf{x} \right]_\times\), where \(\boldsymbol{\mathcal{T}}\) is the adjoint representation of \(SE(3)\) \(\begin{align*} \boldsymbol{\mathcal{T}} = \text{Ad}\left( \mathbf{T} \right) = \text{Ad} \left[ \begin{array}{cc} \mathbf{R} & \mathbf{t} \\ \mathbf{0}^T & 1 \end{array} \right] = \left[ \begin{array}{cc} \mathbf{R} & \left[ \mathbf{t} \right]_\times \mathbf{R} \\ \mathbf{0} & \mathbf{R} \end{array} \right] \end{align*}\)
Compounding via BCH Let \(\mathbf{R}_1 = \exp \left( \left[ \boldsymbol{\rho}_1 \right]_\times \right)\) and \(\mathbf{R}_2 \\ = \exp \left( \left[ \boldsymbol{\rho}_2 \right]_\times \right)\). Then \(\begin{align*} \boldsymbol{\rho}_3 &= \left[ \ln \mathbf{R}_3 \right]_{-\times} = \left[ \ln \left( \mathbf{R}_1 \mathbf{R}_2 \right) \right]_{-\times} \\ &= \left[ \ln \bigl( \exp(\left[ \boldsymbol{\rho}_1 \right]_\times) \exp\left( \left[ \boldsymbol{\rho}_2 \right]_\times \right) \bigr) \right]_{-\times} \\ &= \boldsymbol{\rho}_1 + \boldsymbol{\rho}_2 + \frac{1}{2} \left[ \boldsymbol{\rho}_1 \right]_\times \boldsymbol{\rho}_2 + \frac{1}{12} \left[ \boldsymbol{\rho}_1 \right]_\times \left[ \boldsymbol{\rho}_1 \right]_\times \boldsymbol{\rho}_2 + \frac{1}{12} \left[ \boldsymbol{\rho}_2 \right]_\times \left[ \boldsymbol{\rho}_2 \right]_\times \boldsymbol{\rho}_1 + \ldots \\ &\approx \begin{cases} \mathbf{J}_l^{-1} \left( \boldsymbol{\rho}_2 \right) \boldsymbol{\rho}_1 + \boldsymbol{\rho} _2, \quad \text{if } \boldsymbol{\rho}_1 \ \text{is a small} \\ \mathbf{J}_r^{-1} \left( \boldsymbol{\rho}_1 \right) \boldsymbol{\rho}_2 + \boldsymbol{\rho}_1, \quad \text{if } \boldsymbol{\rho}_2 \ \text{is a small}, \end{cases} \end{align*}\) \(\begin{align*} \boldsymbol{\xi}_3 &= \left[ \ln \left( \mathbf{T}_1 \mathbf{T}_2 \right) \right]_{-\times} \\ &= \left[ \ln \bigl( \exp(\left[ \xi_1 \right]_\times) \exp(\left[ \xi_2 \right]_\times) \bigr) \right]_{-\times} \\ &\approx \begin{cases} \boldsymbol{\mathcal{J}}_l \left( \boldsymbol{\xi}_2 \right)^{-1} \boldsymbol{\xi}_1 + \boldsymbol{\xi}_2, \quad \text{if } \boldsymbol{\xi}_1 \ \text{is a small} \\ \boldsymbol{\mathcal{J}}_r \left( \boldsymbol{\xi}_1 \right)^{-1} \boldsymbol{\xi}_2 + \boldsymbol{\xi}_1, \quad \text{if } \boldsymbol{\xi}_2 \ \text{is a small}. \end{cases} \end{align*}\)

References

  1. Barfoot, T., State Estimation for Robotics