Shortcuts

pypose.Exp

class pypose.Exp(input)[source]

The Exponential map for LieTensor (Lie Algebra).

\[\mathrm{Exp}: \mathcal{g} \mapsto \mathcal{G} \]
Parameters

input (LieTensor) – the input LieTensor (Lie Algebra)

Returns

the output LieTensor (Lie Group)

Return type

LieTensor

List of supported \(\mathrm{Exp}\) map

input ltype

\(\mathcal{g}\) (Lie Algebra)

\(\mapsto\)

\(\mathcal{G}\) (Lie Group)

output ltype

so3_type

\(\mathcal{g}\in\mathbb{R}^{*\times3}\)

\(\mapsto\)

\(\mathcal{G}\in\mathbb{R}^{*\times4}\)

SO3_type

se3_type

\(\mathcal{g}\in\mathbb{R}^{*\times6}\)

\(\mapsto\)

\(\mathcal{G}\in\mathbb{R}^{*\times7}\)

SE3_type

sim3_type

\(\mathcal{g}\in\mathbb{R}^{*\times7}\)

\(\mapsto\)

\(\mathcal{G}\in\mathbb{R}^{*\times8}\)

Sim3_type

rxso3_type

\(\mathcal{g}\in\mathbb{R}^{*\times4}\)

\(\mapsto\)

\(\mathcal{G}\in\mathbb{R}^{*\times5}\)

RxSO3_type

Warning

This function Exp() is different from exp(), which returns a new torch tensor with the exponential of the elements of the input tensor.

  • Input \(\mathbf{x}\)’s ltype is so3_type (input \(\mathbf{x}\) is an instance of so3()):

    If \(\|\mathbf{x}_i\| > \text{eps}\):

    \[\mathbf{y}_i = \left[\mathbf{x}_{i,1}\theta_i, \mathbf{x}_{i,2}\theta_i, \mathbf{x}_{i,3}\theta_i, \cos(\frac{\|\mathbf{x}_i\|}{2})\right], \]

    where \(\theta_i = \frac{1}{\|\mathbf{x}_i\|}\sin(\frac{\|\mathbf{x}_i\|}{2})\),

    otherwise:

    \[\mathbf{y}_i = \left[\mathbf{x}_{i,1}\theta_i,~ \mathbf{x}_{i,2}\theta_i,~ \mathbf{x}_{i,3}\theta_i,~ 1 - \frac{\|\mathbf{x}_i\|^2}{8} + \frac{\|\mathbf{x}_i\|^4}{384} \right], \]

    where \(\theta_i = \frac{1}{2} - \frac{1}{48} \|\mathbf{x}_i\|^2 + \frac{1}{3840} \|\mathbf{x}_i\|^4\).

  • Input \(\mathbf{x}\)’s ltype is se3_type (input \(\mathbf{x}\) is an instance of se3()):

    Let \(\bm{\tau}_i\), \(\bm{\phi}_i\) be the translation and rotation parts of \(\mathbf{x}_i\), respectively; \(\mathbf{y}\) be the output.

    \[\mathbf{y}_i = \left[\mathbf{J}_i\bm{\tau}_i, \mathrm{Exp}(\bm{\phi}_i)\right], \]

    where \(\mathrm{Exp}\) is the Exponential map for so3_type input and \(\mathbf{J}_i\) is the left Jacobian for so3_type input.

  • Input \(\mathbf{x}\)’s ltype is rxso3_type (input \(\mathbf{x}\) is an instance of rxso3()):

    Let \(\bm{\phi}_i\), \(\sigma_i\) be the rotation and scale parts of \(\mathbf{x}_i\), respectively; \(\mathbf{y}\) be the output.

    \[\mathbf{y}_i = \left[\mathrm{Exp}(\bm{\phi}_i), \mathrm{exp}(\sigma_i)\right], \]

    where \(\mathrm{exp}\) is the exponential function.

  • Input \(\mathbf{x}\)’s ltype is sim3_type (input \(\mathbf{x}\) is an instance of sim3()):

    Let \(\bm{\tau}_i\), \(^{s}\bm{\phi}_i\) be the translation and rxso3() parts of \(\mathbf{x}_i\), respectively. \(\bm{\phi}_i = \theta_i\mathbf{n}_i\), \(\sigma_i\) be the rotation and scale parts of \(^{s}\bm{\phi}_i\), \(\boldsymbol{\Phi}_i\) be the skew matrix of \(\bm{\phi}_i\); \(s_i = e^\sigma_i\), \(\mathbf{y}\) be the output.

    \[\mathbf{y}_i = \left[^{s}\mathbf{W}_i\bm{\tau}_i, \mathrm{Exp}(^{s}\bm{\phi}_i)\right], \]

    where

    \[^s\mathbf{W}_i = A\boldsymbol{\Phi}_i + B\boldsymbol{\Phi}_i^2 + C\mathbf{I} \]

    in which if \(\|\sigma_i\| \geq \text{eps}\):

    \[A = \left\{ \begin{array}{ll} \frac{s_i\sin\theta_i\sigma_i + (1-s_i\cos\theta_i)\theta_i} {\theta_i(\sigma_i^2 + \theta_i^2)}, \quad \|\theta_i\| \geq \text{eps}, \\ \frac{(\sigma_i-1)s_i+1}{\sigma_i^2}, \quad \|\theta_i\| < \text{eps}, \end{array} \right. \]
    \[B = \left\{ \begin{array}{ll} \left( C - \frac{(s_i\cos\theta_i-1)\sigma+ s_i\sin\theta_i\sigma_i} {\theta_i^2+\sigma_i^2}\right)\frac{1}{\theta_i^2}, \quad \|\theta_i\| \geq \text{eps}, \\ \frac{s_i\sigma_i^2/2 + s_i-1-\sigma_i s_i}{\sigma_i^3}, \quad \|\theta_i\| < \text{eps}, \end{array} \right. \]
    \[C = \frac{e^{\sigma_i} - 1}{\sigma_i}\mathbf{I} \]

    otherwise:

    \[A = \left\{ \begin{array}{ll} \frac{1-\cos\theta_i}{\theta_i^2}, \quad \|\theta_i\| \geq \text{eps}, \\ \frac{1}{2}, \quad \|\theta_i\| < \text{eps}, \end{array} \right. \]
    \[B = \left\{ \begin{array}{ll} \frac{\theta_i - \sin\theta_i}{\theta_i^3}, \quad \|\theta_i\| \geq \text{eps}, \\ \frac{1}{6}, \quad \|\theta_i\| < \text{eps}, \end{array} \right. \]
    \[C = 1 \]

Note

The detailed explanation of the above \(\mathrm{Exp}\): calculation can be found in the paper:

Assume we have a unit rotation axis \(\mathbf{n}~(\|\mathbf{n}\|=1)\) and rotation angle \(\theta~(0\leq\theta<2\pi)\), let \(\mathbf{x}=\theta\mathbf{n}\), then the corresponding quaternion with unit norm \(\mathbf{q}\) can be represented as:

\[\mathbf{q} = \left[\frac{\sin(\theta/2)}{\theta} \mathbf{x}, \cos(\theta/2) \right]. \]

Given \(\mathbf{x}=\theta\mathbf{n}\), to find its corresponding quaternion \(\mathbf{q}\), we first calculate the rotation angle \(\theta\) using:

\[\theta = \|\mathbf{x}\|. \]

Then, the corresponding quaternion is:

\[\mathbf{q} = \left[\frac{\sin(\|\mathbf{x}\|/2)}{\|\mathbf{x}\|} \mathbf{x}, \cos(\|\mathbf{x}\|/2) \right]. \]

If \(\|\mathbf{x}\|\) is small (\(\|\mathbf{x}\|\le \text{eps}\)), we use the Taylor Expansion form of \(\sin(\|\mathbf{x}\|/2)\) and \(\cos(\|\mathbf{x}\|/2)\).

More details about \(^s\mathbf{W}_i\) in sim3_type can be found in Eq. (5.7):

Examples

  • \(\mathrm{Exp}\): so3 \(\mapsto\) SO3

    >>> x = pp.randn_so3()
    >>> x.Exp() # equivalent to: pp.Exp(x)
    SO3Type LieTensor:
    LieTensor([-0.6627, -0.0447,  0.3492,  0.6610])
    
  • \(\mathrm{Exp}\): se3 \(\mapsto\) SE3

    >>> x = pp.randn_se3(2, requires_grad=True)
    se3Type LieTensor:
    tensor([[ 1.1912,  1.2425, -0.9696,  0.9540, -0.4061, -0.7204],
            [ 0.5964, -1.1894,  0.6451,  1.1373, -2.6733,  0.4142]])
    >>> x.Exp() # equivalent to: pp.Exp(x)
    SE3Type LieTensor:
    tensor([[ 1.6575,  0.8838, -0.1499,  0.4459, -0.1898, -0.3367,  0.8073],
            [ 0.2654, -1.3860,  0.2852,  0.3855, -0.9061,  0.1404,  0.1034]],
            grad_fn=<AliasBackward0>)
    
  • \(\mathrm{Exp}\): rxso3 \(\mapsto\) RxSO3

    >>> x = pp.randn_rxso3(2)
    >>> x.Exp() # equivalent to: pp.Exp(x)
    RxSO3Type LieTensor:
    tensor([[-0.5633, -0.4281,  0.1112,  0.6979,  0.7408],
            [ 0.5089,  0.2016, -0.2015,  0.8122,  1.1692]])
    
  • \(\mathrm{Exp}\): sim3 \(\mapsto\) Sim3

    >>> x = pp.randn_sim3(2)
    >>> x.Exp() # equivalent to: pp.Exp(x)
    Sim3Type LieTensor:
    tensor([[-1.5811,  1.8128, -0.5835,  0.5849,  0.1142, -0.3438,  0.7257,  2.4443],
            [ 0.9574, -0.9265, -0.2385, -0.7309, -0.3875,  0.1404,  0.5440,  1.1945]])
    

Docs

Access documentation for PyPose

View Docs

Tutorials

Get started with tutorials and examples

View Tutorials

Get Started

Find resources and how to start using pypose

View Resources