Shortcuts

pypose.Inv

class pypose.Inv(x)[source]

The inverse of the input lieTensor.

\[\mathrm{Inv}: Y_i = X_i^{-1} \]
Parameters

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

Returns

the output LieTensor (Lie Group or Lie Algebra)

Return type

LieTensor

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

input ltype

LieTensor

\(\mapsto\)

LieTensor

output ltype

SO3_type

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

\(\mapsto\)

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

SO3_type

SE3_type

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

\(\mapsto\)

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

SE3_type

Sim3_type

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

\(\mapsto\)

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

Sim3_type

RxSO3_type

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

\(\mapsto\)

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

RxSO3_type

so3_type

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

\(\mapsto\)

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

so3_type

se3_type

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

\(\mapsto\)

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

se3_type

sim3_type

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

\(\mapsto\)

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

sim3_type

rxso3_type

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

\(\mapsto\)

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

rxso3_type

  • If input \(\mathbf{x}\)’s ltype is SO3_type (input \(\mathbf{x}\) is an instance of SO3()):

    Let \(w_i\), \(\boldsymbol{\nu}_i\) be the scalar and vector parts of \(\mathbf{x}_i\), respectively. \(\mathbf{x}_i=\left[\boldsymbol{\nu}_i, \ w_i \right]\). \(\mathbf{y}\) be the output.

    \[\mathbf{y}_i = \mathrm{conj}(\mathbf{x}_i)=[-\boldsymbol{\nu}_i, \ w_i] \]
  • If input \(\mathbf{x}\)’s ltype is SE3_type (input \(\mathbf{x}\) is an instance of SE3()):

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

    \[\mathbf{y}_i = \left[-\mathrm{Inv}(\mathbf{q}_i)*\mathbf{t}_i, \mathrm{Inv}(\mathbf{q}_i) \right] \]
  • If input \(\mathbf{x}\)’s ltype is RxSO3_type (input \(\mathbf{x}\) is an instance of RxSO3()):

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

    \[\mathbf{y}_i = \left[\mathrm{conj}(\mathbf{q}_i), \ 1/s_i \right] \]
  • If input \(\mathbf{x}\)’s ltype is Sim3_type (input \(\mathbf{x}\) is an instance of Sim3()):

    Let \(\mathbf{t}_i\), \(^s\mathbf{q}_i\) be the translation and RxSO3 parts of \(\mathbf{x}_i\), respectively; \(\mathbf{y}\) be the output.

    \[\mathbf{y}_i = \left[-\mathrm{Inv}(^s\mathbf{q}_i)*\mathbf{t}_i, \mathrm{Inv}(^s\mathbf{q}_i) \right] \]
  • If input \(\mathbf{x}\)’s ltype is so3_type or se3_type or sim3_type or rxso3_type (input \(\mathbf{x}\) is an instance of so3() or se3() or sim3() or rxso3()):

    \[\mathbf{y}_i = -\mathbf{x}_i \]

Example

  • \(\mathrm{Inv}\): SO3 \(\mapsto\) SO3

    >>> x = pp.randn_SO3()
    SO3Type LieTensor:
    tensor([-0.1402, -0.2827,  0.2996,  0.9004])
    >>> x.Inv() # equivalent to: pp.Inv(x)
    SO3Type LieTensor:
    tensor([ 0.1402,  0.2827, -0.2996,  0.9004])
    
  • \(\mathrm{Inv}\): SE3 \(\mapsto\) SE3

    >>> x = pp.randn_SE3()
    SE3Type LieTensor:
    tensor([ 0.6074, -0.7596,  0.8703, -0.3092,  0.2932,  0.9027,  0.0598])
    >>> x.Inv() # equivalent to: pp.Inv(x)
    SE3Type LieTensor:
    tensor([ 0.9475, -0.8764,  0.1938,  0.3092, -0.2932, -0.9027,  0.0598])
    
  • \(\mathrm{Inv}\): RxSO3 \(\mapsto\) RxSO3

    >>> x = pp.randn_RxSO3()
    RxSO3Type LieTensor:
    tensor([-0.5103,  0.4707, -0.3494,  0.6292,  0.9199])
    >>> x.Inv() # equivalent to: pp.Inv(x)
    RxSO3Type LieTensor:
    tensor([ 0.5103, -0.4707,  0.3494,  0.6292,  1.0871])
    
  • \(\mathrm{Inv}\): Sim3 \(\mapsto\) Sim3

    >>> x = pp.randn_Sim3()
    Sim3Type LieTensor:
    tensor([ 0.7056,  1.3140, -0.1995, -0.2444, -0.5250,  0.5504,  0.6014,  1.0543])
    >>> x.Inv() # equivalent to: pp.Inv(x)
    Sim3Type LieTensor:
    tensor([-0.9712, -0.2361,  1.0188,  0.2444,  0.5250, -0.5504,  0.6014,  0.9485])
    
  • \(\mathrm{Inv}\): so3 \(\mapsto\) so3

    >>> x = pp.randn_so3()
    so3Type LieTensor:
    tensor([ 0.0612, -0.7190,  2.6897])
    >>> x.Inv() # equivalent to: pp.Inv(x)
    so3Type LieTensor:
    tensor([-0.0612,  0.7190, -2.6897])
    
  • \(\mathrm{Inv}\): se3 \(\mapsto\) se3

    >>> x = pp.randn_se3()
    se3Type LieTensor:
    tensor([ 0.2837, -1.8318,  1.0104,  2.2385, -0.1980, -0.9487])
    >>> x.Inv() # equivalent to: pp.Inv(x)
    se3Type LieTensor:
    tensor([-0.2837,  1.8318, -1.0104, -2.2385,  0.1980,  0.9487])
    
  • \(\mathrm{Inv}\): rxso3 \(\mapsto\) rxso3

    >>> x = pp.randn_rxso3()
    rxso3Type LieTensor:
    tensor([ 1.0414, -0.0087, -0.4427, -1.1343])
    >>> x.Inv() # equivalent to: pp.Inv(x)
    rxso3Type LieTensor:
    tensor([-1.0414,  0.0087,  0.4427,  1.1343])
    
  • \(\mathrm{Inv}\): sim3 \(\mapsto\) sim3

    >>> x = pp.randn_sim3()
    sim3Type LieTensor:
    tensor([-0.0724,  1.8174,  2.1810, -0.9324, -0.0952, -0.5792,  0.4318])
    >>> x.Inv() # equivalent to: pp.Inv(x)
    sim3Type LieTensor:
    tensor([ 0.0724, -1.8174, -2.1810,  0.9324,  0.0952,  0.5792, -0.4318])
    

Note

Mathematically, only Lie Group has an inverse. For the convenience, we also provide the inverse for the corresponding Lie Algebra. One can validate the results by:

if input \(\mathbf{x}\) is the LieTensor from Lie Group, for example \(\mathbf{x}\)’s ltype is SO3_type :

>>> x = pp.randn_SO3()
>>> x * x.Inv()
SO3Type LieTensor:
LieTensor([0., 0., 0., 1.])

if input \(\mathbf{x}\) is the LieTensor from Lie Algebra, for example \(\mathbf{x}\)’s ltype is so3_type :

>>> x = pp.randn_so3()
>>> x + x.Inv()
tensor([0., 0., 0.])

One can also verify:

>>> x = pp.randn_SO3()
>>> x.Log() + x.Inv().Log()
so3Type LieTensor:
LieTensor([0., 0., 0.])

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