Skip to content

Commit

Permalink
Refactored to simplify extending to non-matrix parametrizations
Browse files Browse the repository at this point in the history
  • Loading branch information
leeclemnet committed Oct 28, 2019
1 parent 01a1554 commit 10e1a64
Show file tree
Hide file tree
Showing 15 changed files with 161 additions and 127 deletions.
11 changes: 6 additions & 5 deletions liegroups/__init__.py
Original file line number Diff line number Diff line change
@@ -1,12 +1,13 @@
"""Special Euclidean and Special Orthogonal Lie groups."""

from liegroups.numpy import SO2
from liegroups.numpy import SE2
from liegroups.numpy import SO3
from liegroups.numpy import SE3
from .numpy import SO2 as SO2
from .numpy import SE2 as SE2
from .numpy import SO3 as SO3
from .numpy import SE3 as SE3


try:
import liegroups.torch
from . import torch
except:
pass

Expand Down
122 changes: 72 additions & 50 deletions liegroups/_base.py
Original file line number Diff line number Diff line change
@@ -1,37 +1,25 @@
from abc import ABCMeta as ABC
from abc import abstractmethod
from abc import ABCMeta, abstractmethod

# support for both python 2 and 3
from future.utils import with_metaclass


# class LieGroupBase(ABC):
class LieGroupBase(with_metaclass(ABC)):
"""Common abstract _base class for Lie groups."""
class LieGroupBase(with_metaclass(ABCMeta)):
"""Common abstract base class for Lie groups."""

@abstractmethod
def __init__(self):
pass

def __repr__(self):
"""Return a string representation of the transformation."""
return "<{}.{}>\n{}".format(self.__class__.__module__, self.__class__.__name__, self.as_matrix()).replace("\n", "\n| ")

@abstractmethod
def adjoint(self):
"""Return the adjoint matrix of the transformation."""
pass

@abstractmethod
def as_matrix(self):
"""Return the matrix representation of the transformation."""
def __repr__(self):
pass

@property
@classmethod
@abstractmethod
def dim(cls):
"""Dimension of the transformation matrix."""
"""Dimension of the underlying representation."""
pass

@property
Expand All @@ -58,12 +46,6 @@ def exp(cls, vec):
"""
pass

@classmethod
@abstractmethod
def from_matrix(cls, mat, normalize=False):
"""Create a transformation from a matrix (safe, but slower)."""
pass

@classmethod
@abstractmethod
def identity(cls):
Expand All @@ -75,24 +57,6 @@ def inv(self):
"""Return the inverse transformation."""
pass

@classmethod
@abstractmethod
def inv_left_jacobian(cls, vec):
"""Inverse of the left Jacobian for the group."""
pass

@classmethod
@abstractmethod
def is_valid_matrix(cls, mat):
"""Check if a matrix is a valid transformation matrix."""
pass

@classmethod
@abstractmethod
def left_jacobian(cls, vec):
"""Left Jacobian for the group."""
pass

@abstractmethod
def log(self):
"""Logarithmic map for the group.
Expand All @@ -105,17 +69,59 @@ def log(self):

@abstractmethod
def normalize(self):
"""Normalize the transformation matrix to ensure it is valid and
"""Normalize the group element to ensure it is valid and
negate the effect of rounding errors.
"""
pass

@abstractmethod
def perturb(self, vec):
"""Perturb the transformation on the left by a vector in its local tangent space.
"""Perturb the group element on the left by a vector in its local tangent space.
"""
pass


class MatrixLieGroupBase(LieGroupBase, with_metaclass(ABCMeta)):
"""Common abstract base class for Matrix Lie Groups."""

def __repr__(self):
"""Return a string representation of the transformation."""
return "<{}.{}>\n{}".format(self.__class__.__module__, self.__class__.__name__, self.as_matrix()).replace("\n", "\n| ")

@abstractmethod
def adjoint(self):
"""Return the adjoint matrix of the transformation."""
pass

@abstractmethod
def as_matrix(self):
"""Return the matrix representation of the transformation."""
pass

@classmethod
@abstractmethod
def from_matrix(cls, mat, normalize=False):
"""Create a transformation from a matrix (safe, but slower)."""
pass

@classmethod
@abstractmethod
def inv_left_jacobian(cls, vec):
"""Inverse of the left Jacobian for the group."""
pass

@classmethod
@abstractmethod
def is_valid_matrix(cls, mat):
"""Check if a matrix is a valid transformation matrix."""
pass

@classmethod
@abstractmethod
def left_jacobian(cls, vec):
"""Left Jacobian for the group."""
pass

@classmethod
@abstractmethod
def vee(cls, mat):
Expand All @@ -135,14 +141,15 @@ def wedge(cls, vec):
pass


class SpecialOrthogonalBase(LieGroupBase, with_metaclass(ABC)):
"""Common abstract _base class for Special Orthogonal groups SO(N)."""
class SOMatrixBase(MatrixLieGroupBase, with_metaclass(ABCMeta)):
"""Common abstract base class for Special Orthogonal Matrix Lie Groups SO(N)."""

def __init__(self, mat):
"""Create a transformation from a rotation matrix (unsafe, but faster)."""
super(SpecialOrthogonalBase, self).__init__()
super(SOMatrixBase, self).__init__()

self.mat = mat
"""Storage for the transformation matrix."""
"""Storage for the rotation matrix."""

def as_matrix(self):
"""Return the matrix representation of the rotation."""
Expand All @@ -157,11 +164,12 @@ def perturb(self, phi):
self.mat = self.__class__.exp(phi).dot(self).mat


class SpecialEuclideanBase(LieGroupBase, with_metaclass(ABC)):
"""Common abstract _base class for Special Euclidean groups SE(N)."""
class SEMatrixBase(MatrixLieGroupBase, with_metaclass(ABCMeta)):
"""Common abstract base class for Special Euclidean Matrix Lie Groups SE(N)."""

def __init__(self, rot, trans):
"""Create a transformation from a translation and a rotation (unsafe, but faster)"""
super(SpecialEuclideanBase, self).__init__()
super(SEMatrixBase, self).__init__()

self.rot = rot
"""Storage for the rotation matrix."""
Expand Down Expand Up @@ -190,3 +198,17 @@ def perturb(self, xi):
def RotationType(cls):
"""Rotation type."""
pass


class VectorLieGroupBase(LieGroupBase, with_metaclass(ABCMeta)):
"""Common abstract base class for Lie Groups with vector parametrizations
(complex, quaternions, dual quaternions)."""

def __init__(self, data):
super(VectorLieGroupBase, self).__init__()

self.data = data

def __repr__(self):
"""Return a string representation of the transformation."""
return "<{}.{}>\n{}".format(self.__class__.__module__, self.__class__.__name__, self.data).replace("\n", "\n| ")
8 changes: 4 additions & 4 deletions liegroups/numpy/__init__.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
"""Numpy implementations of Special Euclidean and Special Orthogonal Lie groups."""

from liegroups.numpy.so2 import SO2
from liegroups.numpy.se2 import SE2
from liegroups.numpy.so3 import SO3
from liegroups.numpy.se3 import SE3
from .so2 import SO2Matrix as SO2
from .se2 import SE2Matrix as SE2
from .so3 import SO3Matrix as SO3
from .se3 import SE3Matrix as SE3

__author__ = "Lee Clement"
__email__ = "lee.clement@robotics.utias.utoronto.ca"
15 changes: 10 additions & 5 deletions liegroups/numpy/_base.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
import numpy as np

from liegroups import _base
from .. import _base


class SpecialOrthogonalBase(_base.SpecialOrthogonalBase):
"""Implementation of methods common to SO(N) using Numpy"""
class SOMatrixBase(_base.SOMatrixBase):
"""Implementation of methods common to SO(N) matrix lie groups using Numpy"""

def dot(self, other):
"""Multiply another rotation or one or more vectors on the left.
Expand Down Expand Up @@ -75,8 +75,8 @@ def normalize(self):
self.mat = U.dot(S).dot(V)


class SpecialEuclideanBase(_base.SpecialEuclideanBase):
"""Implementation of methods common to SE(N) using Numpy"""
class SEMatrixBase(_base.SEMatrixBase):
"""Implementation of methods common to SE(N) matrix lie groups using Numpy"""

def as_matrix(self):
"""Return the matrix representation of the rotation."""
Expand Down Expand Up @@ -160,3 +160,8 @@ def normalize(self):
negate the effect of rounding errors.
"""
self.rot.normalize()


class VectorLieGroupBase(_base.VectorLieGroupBase):
"""Implementation of methods common to vector-parametrized lie groups using Numpy"""
pass
8 changes: 4 additions & 4 deletions liegroups/numpy/se2.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
import numpy as np

from liegroups.numpy import _base
from liegroups.numpy.so2 import SO2
from . import _base
from .so2 import SO2Matrix


class SE2(_base.SpecialEuclideanBase):
class SE2Matrix(_base.SEMatrixBase):
"""Homogeneous transformation matrix in :math:`SE(2)` using active (alibi) transformations.
.. math::
Expand All @@ -29,7 +29,7 @@ class SE2(_base.SpecialEuclideanBase):
"""Dimension of the transformation matrix."""
dof = 3
"""Underlying degrees of freedom (i.e., dimension of the tangent space)."""
RotationType = SO2
RotationType = SO2Matrix

def adjoint(self):
"""Adjoint matrix of the transformation.
Expand Down
22 changes: 11 additions & 11 deletions liegroups/numpy/se3.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
import numpy as np

from liegroups.numpy import _base
from liegroups.numpy.so3 import SO3
from . import _base
from .so3 import SO3Matrix


class SE3(_base.SpecialEuclideanBase):
class SE3Matrix(_base.SEMatrixBase):
"""Homogeneous transformation matrix in :math:`SE(3)` using active (alibi) transformations.
.. math::
Expand All @@ -18,18 +18,18 @@ class SE3(_base.SpecialEuclideanBase):
\\boldsymbol{\\xi}=
\\begin{bmatrix}
\\boldsymbol{\\rho} \\\\ \\boldsymbol{\\phi}
\\end{bmatrix} \\in \\mathbb{R}^6, \\boldsymbol{\\rho} \\in \\mathbb{R}^3, \\boldsymbol{\\phi} \in \\mathbb{R}^3 \\right\\}
\\end{bmatrix} \\in \\mathbb{R}^6, \\boldsymbol{\\rho} \\in \\mathbb{R}^3, \\boldsymbol{\\phi} \\in \\mathbb{R}^3 \\right\\}
:cvar ~liegroups.SE2.dim: Dimension of the rotation matrix.
:cvar ~liegroups.SE2.dof: Underlying degrees of freedom (i.e., dimension of the tangent space).
:ivar rot: Storage for the rotation matrix :math:`\mathbf{C}`.
:ivar trans: Storage for the translation vector :math:`\mathbf{r}`.
:ivar rot: Storage for the rotation matrix :math:`\\mathbf{C}`.
:ivar trans: Storage for the translation vector :math:`\\mathbf{r}`.
"""
dim = 4
"""Dimension of the transformation matrix."""
dof = 6
"""Underlying degrees of freedom (i.e., dimension of the tangent space)."""
RotationType = SO3
RotationType = SO3Matrix

def adjoint(self):
"""Adjoint matrix of the transformation.
Expand Down Expand Up @@ -151,8 +151,8 @@ def left_jacobian_Q_matrix(cls, xi):
rho = xi[0:3] # translation part
phi = xi[3:6] # rotation part

rx = SO3.wedge(rho)
px = SO3.wedge(phi)
rx = cls.RotationType.wedge(rho)
px = cls.RotationType.wedge(phi)

ph = np.linalg.norm(phi)
ph2 = ph * ph
Expand Down Expand Up @@ -195,7 +195,7 @@ def inv_left_jacobian(cls, xi):
if np.isclose(np.linalg.norm(phi), 0.):
return np.identity(cls.dof) - 0.5 * cls.curlywedge(xi)

so3_inv_jac = SO3.inv_left_jacobian(phi)
so3_inv_jac = cls.RotationType.inv_left_jacobian(phi)
Q_mat = cls.left_jacobian_Q_matrix(xi)

jac = np.zeros([cls.dof, cls.dof])
Expand Down Expand Up @@ -225,7 +225,7 @@ def left_jacobian(cls, xi):
if np.isclose(np.linalg.norm(phi), 0.):
return np.identity(cls.dof) + 0.5 * cls.curlywedge(xi)

so3_jac = SO3.left_jacobian(phi)
so3_jac = cls.RotationType.left_jacobian(phi)
Q_mat = cls.left_jacobian_Q_matrix(xi)

jac = np.zeros([cls.dof, cls.dof])
Expand Down
4 changes: 2 additions & 2 deletions liegroups/numpy/so2.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
import numpy as np

from liegroups.numpy import _base
from . import _base


class SO2(_base.SpecialOrthogonalBase):
class SO2Matrix(_base.SOMatrixBase):
"""Rotation matrix in :math:`SO(2)` using active (alibi) transformations.
.. math::
Expand Down

0 comments on commit 10e1a64

Please sign in to comment.