Tangent spaces¶
manif favors Cartesian representations of the tangent spaces. This means that the tangent elements are regular vectors in \(\mathbb{R}^n\), ‘n’ being the dimension of the Lie group.
The ordering of the elements in such vectors matters to correctly interpret them. It impacts the form of all Jacobian matrices and covariances matrices that will be defined on those tangent spaces.
As a reference, this is the way tangent spaces are defined in manif
group |
dimension |
group elements |
tangent elements (in order) |
relation to velocity |
---|---|---|---|---|
Rn |
n |
\(\bf p\) |
\(\bf p\) |
\({\bf p} = {\bf v}\cdot dt\) |
SO(2) |
1 |
\(\bf R\) |
\(\theta\) |
\(\theta = \omega\cdot dt\) |
SO(3) |
3 |
\(\bf R\) |
\(\boldsymbol\theta\) |
\(\boldsymbol\theta = \boldsymbol\omega\cdot dt\) |
SE(2) |
3 |
\(\bf p\), \(\bf R\) |
\(\boldsymbol\rho\), \(\theta\) |
\(\boldsymbol\rho = {\bf v}\cdot dt\) |
SE(3) |
6 |
\(\bf p\), \(\bf R\) |
\(\boldsymbol\rho\), \(\boldsymbol\theta\) |
\(\boldsymbol\rho = {\bf v}\cdot dt\) |
SE_2(3) |
9 |
\(\bf p\), \(\bf R\), \(\bf v\) |
\(\boldsymbol\rho\), \(\boldsymbol\theta\), \(\boldsymbol\nu\) |
\(\boldsymbol\rho = {\bf v}\cdot dt\) |
SGal(3) |
10 |
\(\bf p\), \(\bf R\), \(\bf v\), \(t\) |
\(\boldsymbol\rho\), \(\boldsymbol\nu\), \(\boldsymbol\theta\), \(s\) |
\(\boldsymbol\rho = {\bf v}\cdot dt\) |
As an example, in SE_2(3) the tangent vector \({\boldsymbol\tau}\) is defined by
where \(\boldsymbol\rho\), \(\boldsymbol\theta\) and \(\boldsymbol\nu\) are \(\in \mathbb{R}^3\) and typically correspond respectively to changes in position, orientation and velocity.
A covariances matrix \(\bf Q\) of an element of SE_2(3) can be block-partitioned as follows
All blocks \({\bf Q}_{\bf ij}\) are \(3\times3\) and \({\bf Q}\) is \(9\times9\).